aboutsummaryrefslogtreecommitdiff
path: root/nuttx/syscall
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/syscall')
-rw-r--r--nuttx/syscall/Kconfig4
-rw-r--r--nuttx/syscall/Makefile116
-rw-r--r--nuttx/syscall/README.txt147
-rw-r--r--nuttx/syscall/proxies/Make.defs37
-rw-r--r--nuttx/syscall/stub_lookup.c272
-rw-r--r--nuttx/syscall/stub_lookup.h268
-rw-r--r--nuttx/syscall/stubs/Make.defs38
-rw-r--r--nuttx/syscall/syscall.csv144
8 files changed, 0 insertions, 1026 deletions
diff --git a/nuttx/syscall/Kconfig b/nuttx/syscall/Kconfig
deleted file mode 100644
index ae2bf3130..000000000
--- a/nuttx/syscall/Kconfig
+++ /dev/null
@@ -1,4 +0,0 @@
-#
-# For a description of the syntax of this configuration file,
-# see misc/tools/kconfig-language.txt.
-#
diff --git a/nuttx/syscall/Makefile b/nuttx/syscall/Makefile
deleted file mode 100644
index 4556912be..000000000
--- a/nuttx/syscall/Makefile
+++ /dev/null
@@ -1,116 +0,0 @@
-############################################################################
-# syscall/Makefile
-#
-# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <gnutt@nuttx.org>
-#
-# Redistribution and use in source and binary forms, with or without
-# modification, are permitted provided that the following conditions
-# are met:
-#
-# 1. Redistributions of source code must retain the above copyright
-# notice, this list of conditions and the following disclaimer.
-# 2. Redistributions in binary form must reproduce the above copyright
-# notice, this list of conditions and the following disclaimer in
-# the documentation and/or other materials provided with the
-# distribution.
-# 3. Neither the name NuttX nor the names of its contributors may be
-# used to endorse or promote products derived from this software
-# without specific prior written permission.
-#
-# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
-# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
-# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-# POSSIBILITY OF SUCH DAMAGE.
-#
-###########################################################################
-
--include $(TOPDIR)/Make.defs
-DELIM ?= $(strip /)
-
-include proxies$(DELIM)Make.defs
-include stubs$(DELIM)Make.defs
-
-MKSYSCALL = "$(TOPDIR)$(DELIM)tools$(DELIM)mksyscall$(EXEEXT)"
-CSVFILE = "$(TOPDIR)$(DELIM)syscall$(DELIM)syscall.csv"
-
-STUB_SRCS += stub_lookup.c
-
-ASRCS =
-AOBJS = $(ASRCS:.S=$(OBJEXT))
-
-PROXY_OBJS = $(PROXY_SRCS:.c=$(OBJEXT))
-STUB_OBJS = $(STUB_SRCS:.c=$(OBJEXT))
-
-CSRCS = $(PROXY_SRCS) $(STUB_SRCS)
-COBJS = $(CSRCS:.c=$(OBJEXT))
-
-SRCS = $(ASRCS) $(CSRCS)
-OBJS = $(AOBJS) $(COBJS)
-
-ROOTDEPPATH = --dep-path .
-PROXYDEPPATH = --dep-path proxies
-STUBDEPPATH = --dep-path stubs
-VPATH = proxies:stubs
-
-BIN1 = libproxies$(LIBEXT)
-BIN2 = libstubs$(LIBEXT)
-
-all: $(BIN1) $(BIN2)
-.PHONY: context depend clean distclean
-
-$(AOBJS): %$(OBJEXT): %.S
- $(call ASSEMBLE, $<, $@)
-
-$(COBJS): %$(OBJEXT): %.c
- $(call COMPILE, $<, $@)
-
-$(BIN1): $(PROXY_OBJS)
- $(call ARCHIVE, $@, $(PROXY_OBJS))
-
-$(BIN2): $(STUB_OBJS)
- $(call ARCHIVE, $@, "$(STUB_OBJS)")
-
-.depend: Makefile $(SRCS)
- $(Q) $(MKDEP) $(ROOTDEPPATH) $(PROXYDEPPATH) $(STUBDEPPATH) \
- "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
- $(Q) touch $@
-
-depend: .depend
-
-$(MKSYSCALL):
- $(Q) $(MAKE) -C $(TOPDIR)$(DELIM)tools -f Makefile.host mksyscall
-
-.context: syscall.csv
- $(Q) (cd proxies; $(MKSYSCALL) -p $(CSVFILE);)
- $(Q) (cd stubs; $(MKSYSCALL) -s $(CSVFILE);)
- $(Q) touch $@
-
-context: $(MKSYSCALL) .context
-
-clean:
- $(call DELFILE, $(BIN1))
- $(call DELFILE, $(BIN2))
-ifneq ($(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)
-
--include Make.dep
-
diff --git a/nuttx/syscall/README.txt b/nuttx/syscall/README.txt
deleted file mode 100644
index ed5e6081d..000000000
--- a/nuttx/syscall/README.txt
+++ /dev/null
@@ -1,147 +0,0 @@
-syscall/README.txt
-==================
-
-This directory supports a syscall layer from communication between a
-monolithic, kernel-mode NuttX kernel and a separately built, user-mode
-application set.
-
-With most MCUs, NuttX is built as a flat, single executable image
-containing the NuttX RTOS along with all application code. The RTOS code
-and the application run in the same address space and at the same kernel-
-mode privileges. In order to exploit security features of certain
-processors, an alternative build model is also supported: NuttX can
-be built separately as a monolithic, kernel-mode module and the applications
-can be added as a separately built, user-mode module.
-
-The syscall layer provided in this directory serves as the communication
-layer from the user-mode application into the kernel-mode RTOS. The
-switch from user-mode to kernel-mode is accomplished using software
-interrupts (SWIs). SWIs are implemented differently and named differently
-by different manufacturers but all work essentially the same: A special
-instruction is executed in user-mode that causes a software generated
-interrupt. The software generated interrupt is caught within the kernel
-and handle in kernel-mode.
-
-Header Files
-============
-
-include/syscall.h
-
- This header file supports general access to SWI facilities. It is simply
- a wrapper file that includes include/sys/syscall.h and
- include/arch/syscall.h.
-
-include/sys/syscall.h
-
- The SWIs received by the kernel are distinguish by a code that identifies
- how to process the SWI. This header file defines all such codes understood
- by the NuttX kernel.
-
-include/arch/syscall.h (or arch/<cpu>/include/syscall.h)
-
- This header file is provided by the platform-specific logic and declares
- (or defines) the mechanism for providing software interrupts on this
- platform. The following functions must be declared (or defined) in this
- header file:
-
- - SWI with SYS_ call number and one parameter
-
- uintptr_t sys_call0(unsigned int nbr);
-
- - SWI with SYS_ call number and one parameter
-
- uintptr_t sys_call1(unsigned int nbr, uintptr_t parm1);
-
- - SWI with SYS_ call number and two parameters
-
- uintptr_t sys_call2(unsigned int nbr, uintptr_t parm1, uintptr_t parm2);
-
- - SWI with SYS_ call number and three parameters
-
- uintptr_t sys_call3(unsigned int nbr, uintptr_t parm1,
- uintptr_t parm2, uintptr_t parm3);
-
- - SWI with SYS_ call number and four parameters
-
- uintptr_t sys_call4(unsigned int nbr, uintptr_t parm1, uintptr_t parm2,
- uintptr_t parm3, uintptr_t parm4);
-
- - SWI with SYS_ call number and five parameters
-
- uintptr_t sys_call5(unsigned int nbr, uintptr_t parm1, uintptr_t parm2,
- uintptr_t parm3, uintptr_t parm4, uintptr_t parm5);
-
- - SWI with SYS_ call number and six parameters
-
- uintptr_t sys_call6(unsigned int nbr, uintptr_t parm1, uintptr_t parm2,
- uintptr_t parm3, uintptr_t parm4, uintptr_t parm5,
- uintptr_t parm6);
-Syscall Database
-================
-
-Sycall information is maintained in a database. That "database" is
-implemented as a simple comma-separated-value file, syscall.csv. Most
-spreadsheets programs will accept this format and can be used to maintain
-the syscall database.
-
-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: This CSV file is used both to support the generate of trap information,
-but also for the generation of symbol tables. See nuttx/tools/README.txt
-and nuttx/lib/README.txt for further information.
-
-Auto-Generated Files
-====================
-
-Stubs and proxies for the sycalls are automatically generated from this CSV
-database. Here the following definition is used:
-
- Proxy - A tiny bit of code that executes in the user space. A proxy
- has exactly the same function prototype as does the "real" function
- for which it proxies. However, it only serves to map the function
- call into a syscall, marshaling all of the system call parameters
- as necessary.
-
- Stub - Another tiny bit of code that executes within the NuttX kernel
- that is used to map a software interrupt received by the kernel to
- a kernel function call. The stubs receive the marshaled system
- call data, and perform the actually kernel function call (in
- kernel-mode) on behalf of the proxy function.
-
-Sub-Directories
-===============
-
- stubs - Autogenerated stub files are placed in this directory.
- proxies - Autogenerated proxy files are placed in this directory.
-
-mksyscall
-=========
-
- mksyscall is C program that is used used during the initial NuttX build
- by the logic in the top-level syscall/ directory. Information about the
- stubs and proxies is maintained in a comma separated value (CSV) file
- in the syscall/ directory. The mksyscall program will accept this CVS
- file as input and generate all of the required proxy or stub files as
- output. See tools/README.txt for additional information.
diff --git a/nuttx/syscall/proxies/Make.defs b/nuttx/syscall/proxies/Make.defs
deleted file mode 100644
index a14e3562e..000000000
--- a/nuttx/syscall/proxies/Make.defs
+++ /dev/null
@@ -1,37 +0,0 @@
-############################################################################
-# syscall/proxies/Make.defs
-#
-# Copyright (C) 2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <gnutt@nuttx.org>
-#
-# Redistribution and use in source and binary forms, with or without
-# modification, are permitted provided that the following conditions
-# are met:
-#
-# 1. Redistributions of source code must retain the above copyright
-# notice, this list of conditions and the following disclaimer.
-# 2. Redistributions in binary form must reproduce the above copyright
-# notice, this list of conditions and the following disclaimer in
-# the documentation and/or other materials provided with the
-# distribution.
-# 3. Neither the name NuttX nor the names of its contributors may be
-# used to endorse or promote products derived from this software
-# without specific prior written permission.
-#
-# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
-# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
-# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-# POSSIBILITY OF SUCH DAMAGE.
-#
-############################################################################
-
-PROXY_SRCS := ${shell cd proxies; ls *.c 2>/dev/null }
-
diff --git a/nuttx/syscall/stub_lookup.c b/nuttx/syscall/stub_lookup.c
deleted file mode 100644
index 9d6bf18ae..000000000
--- a/nuttx/syscall/stub_lookup.c
+++ /dev/null
@@ -1,272 +0,0 @@
-/****************************************************************************
- * syscall/syscall_stublookup.c
- *
- * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-#include <syscall.h>
-
-/* This will need to be extended if there are reserved syscall numbers */
-
-#if CONFIG_CONFIG_SYS_RESERVED == 0
-
-/****************************************************************************
- * Pre-processor definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Stub Function Prototypes
- ****************************************************************************/
-
-/* These first system calls are supported regardless of the NuttX
- * configuration
- */
-
-extern uintptr_t STUB__exit(uintptr_t parm1);
-extern uintptr_t STUB_exit(uintptr_t parm1);
-extern uintptr_t STUB_get_errno(void);
-extern uintptr_t STUB_getpid(void);
-extern uintptr_t STUB_sched_getparam(uintptr_t parm1, uintptr_t parm2);
-extern uintptr_t STUB_sched_getscheduler(uintptr_t parm1);
-extern uintptr_t STUB_sched_lock(void);
-extern uintptr_t STUB_sched_lockcount(void);
-extern uintptr_t STUB_sched_rr_get_interval(uintptr_t parm1, uintptr_t parm2);
-extern uintptr_t STUB_sched_setparam(uintptr_t parm1, uintptr_t parm2);
-extern uintptr_t STUB_sched_setscheduler(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3);
-extern uintptr_t STUB_sched_unlock(void);
-extern uintptr_t STUB_sched_yield(void);
-extern uintptr_t STUB_sem_close(uintptr_t parm1);
-extern uintptr_t STUB_sem_destroy(uintptr_t parm1);
-extern uintptr_t STUB_sem_open(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3, uintptr_t parm4, uintptr_t parm5, uintptr_t parm6);
-extern uintptr_t STUB_sem_post(uintptr_t parm1);
-extern uintptr_t STUB_sem_trywait(uintptr_t parm1);
-extern uintptr_t STUB_sem_unlink(uintptr_t parm1);
-extern uintptr_t STUB_sem_wait(uintptr_t parm1);
-extern uintptr_t STUB_set_errno(uintptr_t parm1);
-extern uintptr_t STUB_task_create(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3, uintptr_t parm4, uintptr_t parm5);
-extern uintptr_t STUB_task_delete(uintptr_t parm1);
-extern uintptr_t STUB_task_restart(uintptr_t parm1);
-extern uintptr_t STUB_up_assert(uintptr_t parm1, uintptr_t parm2);
-extern uintptr_t STUB_up_assert_code(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3);
-
-/* The following can be individually enabled */
-
-extern uintptr_t STUB_atexit(uintptr_t parm1);
-extern uintptr_t STUB_waitpid(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3);
-
-/* The following are only defined is signals are supported in the NuttX
- * configuration.
- */
-
-extern uintptr_t STUB_kill(uintptr_t parm1, uintptr_t parm2);
-extern uintptr_t STUB_sigaction(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3);
-extern uintptr_t STUB_sigpending(uintptr_t parm1);
-extern uintptr_t STUB_sigprocmask(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3);
-extern uintptr_t STUB_sigqueue(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3);
-extern uintptr_t STUB_sigsuspend(uintptr_t parm1);
-extern uintptr_t STUB_sigtimedwait(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3);
-extern uintptr_t STUB_sigwaitinfo(uintptr_t parm1, uintptr_t parm2);
-extern uintptr_t STUB_sleep(uintptr_t parm1);
-extern uintptr_t STUB_usleep(uintptr_t parm1);
-
-/* The following are only defined if the system clock is enabled in the
- * NuttX configuration.
- */
-
-extern uintptr_t STUB_clock_systimer(void);
-extern uintptr_t STUB_clock_getres(uintptr_t parm1, uintptr_t parm2);
-extern uintptr_t STUB_clock_gettime(uintptr_t parm1, uintptr_t parm2);
-extern uintptr_t STUB_clock_settime(uintptr_t parm1, uintptr_t parm2);
-extern uintptr_t STUB_gettimeofday(uintptr_t parm1, uintptr_t parm2);
-
-/* The following are defined only if POSIX timers are supported */
-
-extern uintptr_t STUB_timer_create(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3);
-extern uintptr_t STUB_timer_delete(uintptr_t parm1);
-extern uintptr_t STUB_timer_getoverrun(uintptr_t parm1);
-extern uintptr_t STUB_timer_gettime(uintptr_t parm1, uintptr_t parm2);
-extern uintptr_t STUB_timer_settime(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3, uintptr_t parm4);
-
-/* The following are defined if either file or socket descriptor are
- * enabled.
- */
-
-extern uintptr_t STUB_close(uintptr_t parm1);
-extern uintptr_t STUB_ioctl(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3);
-extern uintptr_t STUB_poll(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3);
-extern uintptr_t STUB_read(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3);
-extern uintptr_t STUB_select(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3, uintptr_t parm4, uintptr_t parm5);
-extern uintptr_t STUB_write(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3);
-
-/* The following are defined if file descriptors are enabled */
-
-extern uintptr_t STUB_closedir(uintptr_t parm1);
-extern uintptr_t STUB_dup(uintptr_t parm1);
-extern uintptr_t STUB_dup2(uintptr_t parm1, uintptr_t parm2);
-extern uintptr_t STUB_fcntl(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3, uintptr_t parm4, uintptr_t parm5, uintptr_t parm6);
-extern uintptr_t STUB_lseek(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3);
-extern uintptr_t STUB_mkfifo(uintptr_t parm1, uintptr_t parm2);
-extern uintptr_t STUB_mmap(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3, uintptr_t parm4, uintptr_t parm5, uintptr_t parm6);
-extern uintptr_t STUB_open(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3, uintptr_t parm4, uintptr_t parm5, uintptr_t parm6);
-extern uintptr_t STUB_opendir(uintptr_t parm1);
-extern uintptr_t STUB_pipe(uintptr_t parm1);
-extern uintptr_t STUB_readdir(uintptr_t parm1);
-extern uintptr_t STUB_rewinddir(uintptr_t parm1);
-extern uintptr_t STUB_seekdir(uintptr_t parm1, uintptr_t parm2);
-extern uintptr_t STUB_stat(uintptr_t parm1, uintptr_t parm2);
-extern uintptr_t STUB_statfs(uintptr_t parm1, uintptr_t parm2);
-extern uintptr_t STUB_telldir(uintptr_t parm1);
-
-extern uintptr_t STUB_fs_fdopen(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3);
-extern uintptr_t STUB_sched_getstreams(void);
-
-extern uintptr_t STUB_fsync(uintptr_t parm1);
-extern uintptr_t STUB_mkdir(uintptr_t parm1, uintptr_t parm2);
-extern uintptr_t STUB_mount(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3, uintptr_t parm4, uintptr_t parm5);
-extern uintptr_t STUB_rename(uintptr_t parm1, uintptr_t parm2);
-extern uintptr_t STUB_rmdir(uintptr_t parm1);
-extern uintptr_t STUB_umount(uintptr_t parm1);
-extern uintptr_t STUB_unlink(uintptr_t parm1);
-
-/* The following are defined if pthreads are enabled */
-
-extern uintptr_t STUB_pthread_barrier_destroy(uintptr_t parm1);
-extern uintptr_t STUB_pthread_barrier_init(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3);
-extern uintptr_t STUB_pthread_barrier_wait(uintptr_t parm1);
-extern uintptr_t STUB_pthread_cancel(uintptr_t parm1);
-extern uintptr_t STUB_pthread_cond_broadcast(uintptr_t parm1);
-extern uintptr_t STUB_pthread_cond_destroy(uintptr_t parm1);
-extern uintptr_t STUB_pthread_cond_init(uintptr_t parm1, uintptr_t parm2);
-extern uintptr_t STUB_pthread_cond_signal(uintptr_t parm1);
-extern uintptr_t STUB_pthread_cond_wait(uintptr_t parm1, uintptr_t parm2);
-extern uintptr_t STUB_pthread_create(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3, uintptr_t parm4);
-extern uintptr_t STUB_pthread_detach(uintptr_t parm1);
-extern uintptr_t STUB_pthread_exit(uintptr_t parm1);
-extern uintptr_t STUB_pthread_getschedparam(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3);
-extern uintptr_t STUB_pthread_getspecific(uintptr_t parm1);
-extern uintptr_t STUB_pthread_join(uintptr_t parm1, uintptr_t parm2);
-extern uintptr_t STUB_pthread_key_create(uintptr_t parm1, uintptr_t parm2);
-extern uintptr_t STUB_pthread_key_delete(uintptr_t parm1);
-extern uintptr_t STUB_pthread_mutex_destroy(uintptr_t parm1);
-extern uintptr_t STUB_pthread_mutex_init(uintptr_t parm1, uintptr_t parm2);
-extern uintptr_t STUB_pthread_mutex_lock(uintptr_t parm1);
-extern uintptr_t STUB_pthread_mutex_trylock(uintptr_t parm1);
-extern uintptr_t STUB_pthread_mutex_unlock(uintptr_t parm1);
-extern uintptr_t STUB_pthread_once(uintptr_t parm1, uintptr_t parm2);
-extern uintptr_t STUB_pthread_setcancelstate(uintptr_t parm1, uintptr_t parm2);
-extern uintptr_t STUB_pthread_setschedparam(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3);
-extern uintptr_t STUB_pthread_setschedprio(uintptr_t parm1, uintptr_t parm2);
-extern uintptr_t STUB_pthread_setspecific(uintptr_t parm1, uintptr_t parm2);
-extern uintptr_t STUB_pthread_yield(void);
-
-extern uintptr_t STUB_pthread_cond_timedwait(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3);
-extern uintptr_t STUB_pthread_kill(uintptr_t parm1, uintptr_t parm2);
-extern uintptr_t STUB_pthread_sigmask(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3);
-
-/* The following are defined only if message queues are enabled */
-
-extern uintptr_t STUB_mq_close(uintptr_t parm1);
-extern uintptr_t STUB_mq_notify(uintptr_t parm1, uintptr_t parm2);
-extern uintptr_t STUB_mq_open(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3, uintptr_t parm4, uintptr_t parm5, uintptr_t parm6);
-extern uintptr_t STUB_mq_receive(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3, uintptr_t parm4);
-extern uintptr_t STUB_mq_send(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3, uintptr_t parm4);
-extern uintptr_t STUB_mq_timedreceive(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3, uintptr_t parm4, uintptr_t parm5);
-extern uintptr_t STUB_mq_timedsend(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3, uintptr_t parm4, uintptr_t parm5);
-extern uintptr_t STUB_mq_unlink(uintptr_t parm1);
-
-/* The following are defined only if environment variables are supported */
-
-extern uintptr_t STUB_clearenv(void);
-extern uintptr_t STUB_getenv(uintptr_t parm1);
-extern uintptr_t STUB_putenv(uintptr_t parm1);
-extern uintptr_t STUB_setenv(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3);
-extern uintptr_t STUB_unsetenv(uintptr_t parm1);
-
-/* The following are defined only if networking AND sockets are supported */
-
-extern uintptr_t STUB_accept(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3);
-extern uintptr_t STUB_bind(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3);
-extern uintptr_t STUB_connect(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3);
-extern uintptr_t STUB_getsockopt(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3, uintptr_t parm4, uintptr_t parm5);
-extern uintptr_t STUB_listen(uintptr_t parm1, uintptr_t parm2);
-extern uintptr_t STUB_recv(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3, uintptr_t parm4);
-extern uintptr_t STUB_recvfrom(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3, uintptr_t parm4, uintptr_t parm5, uintptr_t parm6);
-extern uintptr_t STUB_send(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3, uintptr_t parm4);
-extern uintptr_t STUB_sendto(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3, uintptr_t parm4, uintptr_t parm5, uintptr_t parm6);
-extern uintptr_t STUB_setsockopt(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3, uintptr_t parm4, uintptr_t parm5);
-extern uintptr_t STUB_socket(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3);
-
-/* The following is defined only if CONFIG_TASK_NAME_SIZE > 0 */
-
-extern uintptr_t STUB_prctl(uintptr_t parm1, uintptr_t parm2, uintptr_t parm3, uintptr_t parm4, uintptr_t parm5);
-
-/****************************************************************************
- * Public Data
- ****************************************************************************/
-
-/* Stub lookup tables. Each table is indexed by the system call numbers
- * defined above. Given the system call number, the corresponding entry in
- * these tables describes how to call the stub dispatch function.
- */
-
-const union syscall_stubfunc_u g_stublookup[SYS_nsyscalls] =
-{
-# undef STUB_LOOKUP1
-# define STUB_LOOKUP1(n,p) (union syscall_stubfunc_u)p
-# undef STUB_LOOKUP
-# define STUB_LOOKUP(n,p) , (union syscall_stubfunc_u)p
-# include "stub_lookup.h"
-};
-
-const uint8_t g_stubnparms[SYS_nsyscalls] =
-{
-# undef STUB_LOOKUP1
-# define STUB_LOOKUP1(n,p) n
-# undef STUB_LOOKUP
-# define STUB_LOOKUP(n,p) , n
-# include "stub_lookup.h"
-};
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-#endif /* CONFIG_CONFIG_SYS_RESERVED */
diff --git a/nuttx/syscall/stub_lookup.h b/nuttx/syscall/stub_lookup.h
deleted file mode 100644
index 1c749ee62..000000000
--- a/nuttx/syscall/stub_lookup.h
+++ /dev/null
@@ -1,268 +0,0 @@
-/****************************************************************************
- * syscall/stub_lookup.h
- *
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/* STUB_LOOKUP must be defined before including this file.
- *
- * These first system calls are supported regardless of the NuttX
- * configuration
- */
-
-STUB_LOOKUP1(1, STUB__exit) /* SYS__exit */
-STUB_LOOKUP(1, STUB_exit) /* SYS_exit */
-STUB_LOOKUP(0, STUB_get_errno) /* SYS_get_errno */
-STUB_LOOKUP(0, STUB_getpid) /* SYS_getpid */
-STUB_LOOKUP(2, STUB_sched_getparam) /* SYS_sched_getparam */
-STUB_LOOKUP(1, STUB_sched_getscheduler) /* SYS_sched_getscheduler */
-STUB_LOOKUP(0, STUB_sched_lock) /* SYS_sched_lock */
-STUB_LOOKUP(0, STUB_sched_lockcount) /* SYS_sched_lockcount */
-STUB_LOOKUP(2, STUB_sched_rr_get_interval) /* SYS_sched_rr_get_interval */
-STUB_LOOKUP(2, STUB_sched_setparam) /* SYS_sched_setparam */
-STUB_LOOKUP(3, STUB_sched_setscheduler) /* SYS_sched_setscheduler */
-STUB_LOOKUP(0, STUB_sched_unlock) /* SYS_sched_unlock */
-STUB_LOOKUP(0, STUB_sched_yield) /* SYS_sched_yield */
-STUB_LOOKUP(1, STUB_sem_close) /* SYS_sem_close */
-STUB_LOOKUP(2, STUB_sem_destroy) /* SYS_sem_destroy */
-STUB_LOOKUP(6, STUB_sem_open) /* SYS_sem_open */
-STUB_LOOKUP(1, STUB_sem_post) /* SYS_sem_post */
-STUB_LOOKUP(1, STUB_sem_trywait) /* SYS_sem_trywait */
-STUB_LOOKUP(1, STUB_sem_unlink) /* SYS_sem_unlink */
-STUB_LOOKUP(1, STUB_sem_wait) /* SYS_sem_wait */
-STUB_LOOKUP(1, STUB_set_errno) /* SYS_set_errno */
-STUB_LOOKUP(5, STUB_task_create) /* SYS_task_create */
-STUB_LOOKUP(1, STUB_task_delete) /* SYS_task_delete */
-STUB_LOOKUP(1, STUB_task_restart) /* SYS_task_restart */
-STUB_LOOKUP(2, STUB_up_assert) /* SYS_up_assert */
-STUB_LOOKUP(3, STUB_up_assert_code) /* SYS_up_assert_code */
-
-/* The following can be individually enabled */
-
-#ifdef CONFIG_SCHED_ATEXIT
- STUB_LOOKUP(1, STUB_atexit) /* SYS_atexit */
-#endif
-
-#ifdef CONFIG_SCHED_ONEXIT
- STUB_LOOKUP(2, STUB_onexit) /* SYS_onexit */
-#endif
-
-#ifdef CONFIG_SCHED_WAITPID
- STUB_LOOKUP(3, STUB_waitpid) /* SYS_waitpid */
-#endif
-
-/* The following are only defined is signals are supported in the NuttX
- * configuration.
- */
-
-#ifndef CONFIG_DISABLE_SIGNALS
- STUB_LOOKUP(2, STUB_kill) /* SYS_kill */
- STUB_LOOKUP(3, STUB_sigaction) /* SYS_sigaction */
- STUB_LOOKUP(1, STUB_sigpending) /* SYS_sigpending */
- STUB_LOOKUP(3, STUB_sigprocmask) /* SYS_sigprocmask */
- STUB_LOOKUP(3, STUB_sigqueue) /* SYS_sigqueue */
- STUB_LOOKUP(1, STUB_sigsuspend) /* SYS_sigsuspend */
- STUB_LOOKUP(3, STUB_sigtimedwait) /* SYS_sigtimedwait */
- STUB_LOOKUP(2, STUB_sigwaitinfo) /* SYS_sigwaitinfo */
- STUB_LOOKUP(1, STUB_sleep) /* SYS_sleep */
- STUB_LOOKUP(1, STUB_usleep) /* SYS_usleep */
-#endif
-
-/* The following are only defined if the system clock is enabled in the
- * NuttX configuration.
- */
-
-#ifndef CONFIG_DISABLE_CLOCK
- STUB_LOOKUP(0, STUB_clock_systimer) /* SYS_clock_systimer */
- STUB_LOOKUP(2, STUB_clock_getres) /* SYS_clock_getres */
- STUB_LOOKUP(2, STUB_clock_gettime) /* SYS_clock_gettime */
- STUB_LOOKUP(2, STUB_clock_settime) /* SYS_clock_settime */
- STUB_LOOKUP(2, STUB_gettimeofday) /* SYS_gettimeofday */
-#endif
-
-/* The following are defined only if POSIX timers are supported */
-
-#ifndef CONFIG_DISABLE_POSIX_TIMERS
- STUB_LOOKUP(3, STUB_timer_create) /* SYS_timer_create */
- STUB_LOOKUP(1, STUB_timer_delete) /* SYS_timer_delete */
- STUB_LOOKUP(1, STUB_timer_getoverrun) /* SYS_timer_getoverrun */
- STUB_LOOKUP(2, STUB_timer_gettime) /* SYS_timer_gettime */
- STUB_LOOKUP(4, STUB_timer_settime) /* SYS_timer_settime */
-#endif
-
-/* The following are defined if either file or socket descriptor are
- * enabled.
- */
-
-#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
- STUB_LOOKUP(1, STUB_close) /* SYS_close */
- STUB_LOOKUP(3, STUB_ioctl) /* SYS_ioctl */
- STUB_LOOKUP(3, STUB_read) /* SYS_read */
- STUB_LOOKUP(3, STUB_write) /* SYS_write */
-# ifndef CONFIG_DISABLE_POLL
- STUB_LOOKUP(3, STUB_poll) /* SYS_poll */
- STUB_LOOKUP(5, STUB_select) /* SYS_select */
-# endif
-#endif
-
-/* The following are defined if file descriptors are enabled */
-
-#if CONFIG_NFILE_DESCRIPTORS > 0
- STUB_LOOKUP(1, STUB_closedir) /* SYS_closedir */
- STUB_LOOKUP(1, STUB_dup) /* SYS_dup */
- STUB_LOOKUP(2, STUB_dup2) /* SYS_dup2 */
- STUB_LOOKUP(6, STUB_fcntl) /* SYS_fcntl */
- STUB_LOOKUP(3, STUB_lseek) /* SYS_lseek */
- STUB_LOOKUP(2, STUB_mkfifo) /* SYS_mkfifo */
- STUB_LOOKUP(6, STUB_mmap) /* SYS_mmap */
- STUB_LOOKUP(6, STUB_open) /* SYS_open */
- STUB_LOOKUP(1, STUB_opendir) /* SYS_opendir */
- STUB_LOOKUP(1, STUB_pipe) /* SYS_pipe */
- STUB_LOOKUP(1, STUB_readdir) /* SYS_readdir */
- STUB_LOOKUP(1, STUB_rewinddir) /* SYS_rewinddir */
- STUB_LOOKUP(2, STUB_seekdir) /* SYS_seekdir */
- STUB_LOOKUP(2, STUB_stat) /* SYS_stat */
- STUB_LOOKUP(2, STUB_statfs) /* SYS_statfs */
- STUB_LOOKUP(1, STUB_telldir) /* SYS_telldir */
-
-# if CONFIG_NFILE_STREAMS > 0
- STUB_LOOKUP(3, STUB_fs_fdopen) /* SYS_fs_fdopen */
- STUB_LOOKUP(0, STUB_sched_getstreams) /* SYS_sched_getstreams */
-#endif
-
-# if !defined(CONFIG_DISABLE_MOUNTPOINT)
- STUB_LOOKUP(1, STUB_fsync) /* SYS_fsync */
- STUB_LOOKUP(2, STUB_mkdir) /* SYS_mkdir */
- STUB_LOOKUP(5, STUB_mount) /* SYS_mount */
- STUB_LOOKUP(2, STUB_rename) /* SYS_rename */
- STUB_LOOKUP(1, STUB_rmdir) /* SYS_rmdir */
- STUB_LOOKUP(1, STUB_umount) /* SYS_umount */
- STUB_LOOKUP(1, STUB_unlink) /* SYS_unlink */
-# endif
-#endif
-
-/* The following are defined if pthreads are enabled */
-
-#ifndef CONFIG_DISABLE_PTHREAD
- STUB_LOOKUP(1, STUB_pthread_barrier_destroy) /* SYS_pthread_barrier_destroy */
- STUB_LOOKUP(3, STUB_pthread_barrier_init) /* SYS_pthread_barrier_init */
- STUB_LOOKUP(1, STUB_pthread_barrier_wait) /* SYS_pthread_barrier_wait */
- STUB_LOOKUP(1, STUB_pthread_cancel) /* SYS_pthread_cancel */
- STUB_LOOKUP(1, STUB_pthread_cond_broadcast) /* SYS_pthread_cond_broadcast */
- STUB_LOOKUP(1, STUB_pthread_cond_destroy) /* SYS_pthread_cond_destroy */
- STUB_LOOKUP(2, STUB_pthread_cond_init) /* SYS_pthread_cond_init */
- STUB_LOOKUP(1, STUB_pthread_cond_signal) /* SYS_pthread_cond_signal */
- STUB_LOOKUP(2, STUB_pthread_cond_wait) /* SYS_pthread_cond_wait */
- STUB_LOOKUP(4, STUB_pthread_create) /* SYS_pthread_create */
- STUB_LOOKUP(1, STUB_pthread_detach) /* SYS_pthread_detach */
- STUB_LOOKUP(1, STUB_pthread_exit) /* SYS_pthread_exit */
- STUB_LOOKUP(3, STUB_pthread_getschedparam) /* SYS_pthread_getschedparam */
- STUB_LOOKUP(1, STUB_pthread_getspecific) /* SYS_pthread_getspecific */
- STUB_LOOKUP(2, STUB_pthread_join) /* SYS_pthread_join */
- STUB_LOOKUP(2, STUB_pthread_key_create) /* SYS_pthread_key_create */
- STUB_LOOKUP(1, STUB_pthread_key_delete) /* SYS_pthread_key_delete */
- STUB_LOOKUP(1, STUB_pthread_mutex_destroy) /* SYS_pthread_mutex_destroy */
- STUB_LOOKUP(2, STUB_pthread_mutex_init) /* SYS_pthread_mutex_init */
- STUB_LOOKUP(1, STUB_pthread_mutex_lock) /* SYS_pthread_mutex_lock */
- STUB_LOOKUP(1, STUB_pthread_mutex_trylock) /* SYS_pthread_mutex_trylock */
- STUB_LOOKUP(1, STUB_pthread_mutex_unlock) /* SYS_pthread_mutex_unlock */
- STUB_LOOKUP(2, STUB_pthread_once) /* SYS_pthread_once */
- STUB_LOOKUP(2, STUB_pthread_setcancelstate) /* SYS_pthread_setcancelstate */
- STUB_LOOKUP(3, STUB_pthread_setschedparam) /* SYS_pthread_setschedparam */
- STUB_LOOKUP(2, STUB_pthread_setschedprio) /* SYS_pthread_setschedprio */
- STUB_LOOKUP(2, STUB_pthread_setspecific) /* SYS_pthread_setspecific */
- STUB_LOOKUP(0, STUB_pthread_yield) /* SYS_pthread_yield */
-# ifndef CONFIG_DISABLE_SIGNAL
- STUB_LOOKUP(3, STUB_pthread_cond_timedwait) /* SYS_pthread_cond_timedwait */
- STUB_LOOKUP(2, STUB_pthread_kill) /* SYS_pthread_kill */
- STUB_LOOKUP(3, STUB_pthread_sigmask) /* SYS_pthread_sigmask */
-# endif
-#endif
-
-/* The following are defined only if message queues are enabled */
-
-#ifndef CONFIG_DISABLE_MQUEUE
- STUB_LOOKUP(1, STUB_mq_close) /* SYS_mq_close */
- STUB_LOOKUP(2, STUB_mq_notify) /* SYS_mq_notify */
- STUB_LOOKUP(6, STUB_mq_open) /* SYS_mq_open */
- STUB_LOOKUP(4, STUB_mq_receive) /* SYS_mq_receive */
- STUB_LOOKUP(4, STUB_mq_send) /* SYS_mq_send */
- STUB_LOOKUP(5, STUB_mq_timedreceive) /* SYS_mq_timedreceive */
- STUB_LOOKUP(5, STUB_mq_timedsend) /* SYS_mq_timedsend */
- STUB_LOOKUP(1, STUB_mq_unlink) /* SYS_mq_unlink */
-#endif
-
-/* The following are defined only if environment variables are supported */
-
-#ifndef CONFIG_DISABLE_ENVIRON
- STUB_LOOKUP(0, STUB_clearenv) /* SYS_clearenv */
- STUB_LOOKUP(1, STUB_getenv) /* SYS_getenv */
- STUB_LOOKUP(1, STUB_putenv) /* SYS_putenv */
- STUB_LOOKUP(3, STUB_setenv) /* SYS_setenv */
- STUB_LOOKUP(1, STUB_unsetenv) /* SYS_unsetenv */
-#endif
-
-/* The following are defined only if networking AND sockets are supported */
-
-#if CONFIG_NSOCKET_DESCRIPTORS > 0 && defined(CONFIG_NET)
- STUB_LOOKUP(3, STUB_accept) /* SYS_accept */
- STUB_LOOKUP(3, STUB_bind) /* SYS_bind */
- STUB_LOOKUP(3, STUB_connect) /* SYS_connect */
- STUB_LOOKUP(5, STUB_getsockopt) /* SYS_getsockopt */
- STUB_LOOKUP(2, STUB_listen) /* SYS_listen */
- STUB_LOOKUP(4, STUB_recv) /* SYS_recv */
- STUB_LOOKUP(6, STUB_recvfrom) /* SYS_recvfrom */
- STUB_LOOKUP(4, STUB_send) /* SYS_send */
- STUB_LOOKUP(6, STUB_sendto) /* SYS_sendto */
- STUB_LOOKUP(5, STUB_setsockopt) /* SYS_setsockopt */
- STUB_LOOKUP(3, STUB_socket) /* SYS_socket */
-#endif
-
-/* The following is defined only if CONFIG_TASK_NAME_SIZE > 0 */
-
-#if CONFIG_TASK_NAME_SIZE > 0
- STUB_LOOKUP(5, STUB_prctl) /* SYS_prctl */
-#endif
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-
diff --git a/nuttx/syscall/stubs/Make.defs b/nuttx/syscall/stubs/Make.defs
deleted file mode 100644
index 0f40052c0..000000000
--- a/nuttx/syscall/stubs/Make.defs
+++ /dev/null
@@ -1,38 +0,0 @@
-############################################################################
-# syscall/stubs/Make.defs
-#
-# Copyright (C) 2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <gnutt@nuttx.org>
-#
-# Redistribution and use in source and binary forms, with or without
-# modification, are permitted provided that the following conditions
-# are met:
-#
-# 1. Redistributions of source code must retain the above copyright
-# notice, this list of conditions and the following disclaimer.
-# 2. Redistributions in binary form must reproduce the above copyright
-# notice, this list of conditions and the following disclaimer in
-# the documentation and/or other materials provided with the
-# distribution.
-# 3. Neither the name NuttX nor the names of its contributors may be
-# used to endorse or promote products derived from this software
-# without specific prior written permission.
-#
-# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
-# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
-# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-# POSSIBILITY OF SUCH DAMAGE.
-#
-############################################################################
-
-STUB_SRCS := ${shell cd stubs; ls *.c 2>/dev/null }
-
-
diff --git a/nuttx/syscall/syscall.csv b/nuttx/syscall/syscall.csv
deleted file mode 100644
index 5bc52a71d..000000000
--- a/nuttx/syscall/syscall.csv
+++ /dev/null
@@ -1,144 +0,0 @@
-"_exit","unistd.h","","void","int"
-"accept","sys/socket.h","CONFIG_NSOCKET_DESCRIPTORS > 0 && defined(CONFIG_NET)","int","int","struct sockaddr*","socklen_t*"
-"atexit","stdlib.h","defined(CONFIG_SCHED_ATEXIT)","int","void (*)(void)"
-"bind","sys/socket.h","CONFIG_NSOCKET_DESCRIPTORS > 0 && defined(CONFIG_NET)","int","int","FAR const struct sockaddr*","socklen_t"
-"clearenv","stdlib.h","!defined(CONFIG_DISABLE_ENVIRON)","int"
-"clock_getres","time.h","!defined(CONFIG_DISABLE_CLOCK)","int","clockid_t","struct timespec*"
-"clock_gettime","time.h","!defined(CONFIG_DISABLE_CLOCK)","int","clockid_t","struct timespec*"
-"clock_settime","time.h","!defined(CONFIG_DISABLE_CLOCK)","int","clockid_t","const struct timespec*"
-"close","unistd.h","CONFIG_NSOCKET_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0","int","int"
-"closedir","dirent.h","CONFIG_NFILE_DESCRIPTORS > 0","int","FAR DIR*"
-"connect","sys/socket.h","CONFIG_NSOCKET_DESCRIPTORS > 0 && defined(CONFIG_NET)","int","int","FAR const struct sockaddr*","socklen_t"
-"dup","unistd.h","CONFIG_NFILE_DESCRIPTORS > 0","int","int"
-"dup2","unistd.h","CONFIG_NFILE_DESCRIPTORS > 0","int","int","int"
-"exit","stdlib.h","","void","int"
-"fcntl","fcntl.h","CONFIG_NFILE_DESCRIPTORS > 0","int","int","int","..."
-"fs_fdopen","nuttx/fs/fs.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","FAR struct file_struct*","int","int","FAR _TCB*"
-"fsync","unistd.h","CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_DISABLE_MOUNTPOINT)","int","int"
-"get_errno","errno.h","","int"
-"getenv","stdlib.h","!defined(CONFIG_DISABLE_ENVIRON)","FAR char*","FAR const char*"
-"getpid","unistd.h","","pid_t"
-"getsockopt","sys/socket.h","CONFIG_NSOCKET_DESCRIPTORS > 0 && defined(CONFIG_NET)","int","int","int","int","FAR void*","FAR socklen_t*"
-"gettimeofday","sys/time.h","!defined(CONFIG_DISABLE_CLOCK)","int","struct timeval*","FAR void*"
-"ioctl","sys/ioctl.h","CONFIG_NSOCKET_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0","int","int","int","unsigned long"
-"kill","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","pid_t","int"
-"listen","sys/socket.h","CONFIG_NSOCKET_DESCRIPTORS > 0 && defined(CONFIG_NET)","int","int","int"
-"lseek","unistd.h","CONFIG_NFILE_DESCRIPTORS > 0","off_t","int","off_t","int"
-"mkdir","sys/stat.h","CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_DISABLE_MOUNTPOINT)","int","FAR const char*","mode_t"
-"mkfifo","sys/stat.h","CONFIG_NFILE_DESCRIPTORS > 0","int","FAR const char*","mode_t"
-"mmap","sys/mman.h","CONFIG_NFILE_DESCRIPTORS > 0","FAR void*","FAR void*","size_t","int","int","int","off_t"
-"mount","sys/mount.h","CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_DISABLE_MOUNTPOINT)","int","const char*","const char*","const char*","unsigned long","const void*"
-"mq_close","mqueue.h","!defined(CONFIG_DISABLE_MQUEUE)","int","mqd_t"
-"mq_notify","mqueue.h","!defined(CONFIG_DISABLE_SIGNALS) && !defined(CONFIG_DISABLE_MQUEUE)","int","mqd_t","const struct sigevent*"
-"mq_open","mqueue.h","!defined(CONFIG_DISABLE_MQUEUE)","mqd_t","const char*","int","..."
-"mq_receive","mqueue.h","!defined(CONFIG_DISABLE_MQUEUE)","ssize_t","mqd_t","void*","size_t","int*"
-"mq_send","mqueue.h","!defined(CONFIG_DISABLE_MQUEUE)","int","mqd_t","const void*","size_t","int"
-"mq_timedreceive","mqueue.h","!defined(CONFIG_DISABLE_MQUEUE)","ssize_t","mqd_t","void*","size_t","int*","const struct timespec*"
-"mq_timedsend","mqueue.h","!defined(CONFIG_DISABLE_MQUEUE)","int","mqd_t","const char*","size_t","int","const struct timespec*"
-"mq_unlink","mqueue.h","!defined(CONFIG_DISABLE_MQUEUE)","int","const char*"
-"on_exit","stdlib.h","defined(CONFIG_SCHED_ONEXIT)","int","CODE void (*func)(int, FAR void *)","FAR void *"
-"open","fcntl.h","CONFIG_NFILE_DESCRIPTORS > 0","int","const char*","int","..."
-"opendir","dirent.h","CONFIG_NFILE_DESCRIPTORS > 0","FAR DIR*","FAR const char*"
-"pipe","unistd.h","CONFIG_NFILE_DESCRIPTORS > 0","int","int [2]|int*"
-"prctl","sys/prctl.h", "CONFIG_TASK_NAME_SIZE > 0","int","int","..."
-"clock_systimer","nuttx/clock.h","!defined(CONFIG_DISABLE_CLOCK)","uint32_t"
-"poll","poll.h","!defined(CONFIG_DISABLE_POLL) && (CONFIG_NSOCKET_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0)","int","FAR struct pollfd*","nfds_t","int"
-"posix_spawnp", defined(CONFIG_BINFMT_EXEPATH), "int","FAR pid_t *","FAR const char *","FAR const posix_spawn_file_actions_t *","FAR const posix_spawnattr_t *","FAR char *const []","FAR char *const []"
-"posix_spawn", !defined(CONFIG_BINFMT_EXEPATH), "int","FAR pid_t *","FAR const char *","FAR const posix_spawn_file_actions_t *","FAR const posix_spawnattr_t *","FAR char *const []","FAR char *const []"
-"pthread_barrier_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_barrier_t*"
-"pthread_barrier_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_barrier_t*","FAR const pthread_barrierattr_t*","unsigned int"
-"pthread_barrier_wait","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_barrier_t*"
-"pthread_cancel","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","pthread_t"
-"pthread_cond_broadcast","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_cond_t*"
-"pthread_cond_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_cond_t*"
-"pthread_cond_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_cond_t*","FAR pthread_condattr_t*"
-"pthread_cond_signal","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_cond_t*"
-"pthread_cond_timedwait","pthread.h","!defined(CONFIG_DISABLE_SIGNALS) && !defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_cond_t*","FAR pthread_mutex_t*","FAR const struct timespec*"
-"pthread_cond_wait","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_cond_t*","FAR pthread_mutex_t*"
-"pthread_create","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_t*","FAR pthread_attr_t*","pthread_startroutine_t","pthread_addr_t"
-"pthread_detach","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","pthread_t"
-"pthread_exit","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","void","pthread_addr_t"
-"pthread_getschedparam","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","pthread_t","FAR int*","FAR struct sched_param*"
-"pthread_getspecific","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","FAR void*","pthread_key_t"
-"pthread_join","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","pthread_t","FAR pthread_addr_t*"
-"pthread_key_create","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_key_t*","CODE void (*)(FAR void*)"
-"pthread_key_delete","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","pthread_key_t"
-"pthread_kill","pthread.h","!defined(CONFIG_DISABLE_SIGNALS) && !defined(CONFIG_DISABLE_PTHREAD)","int","pthread_t","int"
-"pthread_mutex_destroy","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutex_t*"
-"pthread_mutex_init","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutex_t*","FAR pthread_mutexattr_t*"
-"pthread_mutex_lock","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutex_t*"
-"pthread_mutex_trylock","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutex_t*"
-"pthread_mutex_unlock","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_mutex_t*"
-"pthread_once","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","FAR pthread_once_t*","CODE void (*)(void)"
-"pthread_setcancelstate","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","int","FAR int*"
-"pthread_setschedparam","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","pthread_t","int","FAR const struct sched_param*"
-"pthread_setschedprio","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","pthread_t","int"
-"pthread_setspecific","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","int","pthread_key_t","FAR void*"
-"pthread_sigmask","pthread.h","!defined(CONFIG_DISABLE_SIGNALS) && !defined(CONFIG_DISABLE_PTHREAD)","int","int","FAR const sigset_t*","FAR sigset_t*"
-"pthread_yield","pthread.h","!defined(CONFIG_DISABLE_PTHREAD)","void"
-"putenv","stdlib.h","!defined(CONFIG_DISABLE_ENVIRON)","int","FAR const char*"
-"read","unistd.h","CONFIG_NSOCKET_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0","ssize_t","int","FAR void*","size_t"
-"readdir","dirent.h","CONFIG_NFILE_DESCRIPTORS > 0","FAR struct dirent*","FAR DIR*"
-"recv","sys/socket.h","CONFIG_NSOCKET_DESCRIPTORS > 0 && defined(CONFIG_NET)","ssize_t","int","FAR void*","size_t","int"
-"recvfrom","sys/socket.h","CONFIG_NSOCKET_DESCRIPTORS > 0 && defined(CONFIG_NET)","ssize_t","int","FAR void*","size_t","int","FAR struct sockaddr*","FAR socklen_t*"
-"rename","stdio.h","CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_DISABLE_MOUNTPOINT)","int","FAR const char*","FAR const char*"
-"rewinddir","dirent.h","CONFIG_NFILE_DESCRIPTORS > 0","void","FAR DIR*"
-"rmdir","unistd.h","CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_DISABLE_MOUNTPOINT)","int","FAR const char*"
-"sched_getparam","sched.h","","int","pid_t","struct sched_param*"
-"sched_getscheduler","sched.h","","int","pid_t"
-"sched_getstreams","nuttx/sched.h","CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_NFILE_STREAMS > 0","FAR struct streamlist*"
-"sched_lock","sched.h","","int"
-"sched_lockcount","sched.h","","int32_t"
-"sched_rr_get_interval","sched.h","","int","pid_t","struct timespec*"
-"sched_setparam","sched.h","","int","pid_t","const struct sched_param*"
-"sched_setscheduler","sched.h","","int","pid_t","int","const struct sched_param*"
-"sched_unlock","sched.h","","int"
-"sched_yield","sched.h","","int"
-"seekdir","dirent.h","CONFIG_NFILE_DESCRIPTORS > 0","void","FAR DIR*","off_t"
-"select","sys/select.h","!defined(CONFIG_DISABLE_POLL) && (CONFIG_NSOCKET_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0)","int","int","FAR fd_set*","FAR fd_set*","FAR fd_set*","FAR struct timeval*"
-"sem_close","semaphore.h","","int","FAR sem_t*"
-"sem_destroy","semaphore.h","","int","FAR sem_t*"
-"sem_open","semaphore.h","","FAR sem_t*","FAR const char*","int","..."
-"sem_post","semaphore.h","","int","FAR sem_t*"
-"sem_trywait","semaphore.h","","int","FAR sem_t*"
-"sem_unlink","semaphore.h","","int","FAR const char*"
-"sem_wait","semaphore.h","","int","FAR sem_t*"
-"send","sys/socket.h","CONFIG_NSOCKET_DESCRIPTORS > 0 && defined(CONFIG_NET)","ssize_t","int","FAR const void*","size_t","int"
-"sendto","sys/socket.h","CONFIG_NSOCKET_DESCRIPTORS > 0 && defined(CONFIG_NET)","ssize_t","int","FAR const void*","size_t","int","FAR const struct sockaddr*","socklen_t"
-"set_errno","errno.h","","void","int"
-"setenv","stdlib.h","!defined(CONFIG_DISABLE_ENVIRON)","int","const char*","const char*","int"
-"setsockopt","sys/socket.h","CONFIG_NSOCKET_DESCRIPTORS > 0 && defined(CONFIG_NET)","int","int","int","int","FAR const void*","socklen_t"
-"sigaction","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","int","FAR const struct sigaction*","FAR struct sigaction*"
-"sigpending","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","FAR sigset_t*"
-"sigprocmask","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","int","FAR const sigset_t*","FAR sigset_t*"
-"sigqueue","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","int","int","union sigval|FAR void *|sival_ptr"
-"sigsuspend","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","FAR const sigset_t*"
-"sigtimedwait","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","FAR const sigset_t*","FAR struct siginfo*","FAR const struct timespec*"
-"sigwaitinfo","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","FAR const sigset_t*","FAR struct siginfo*"
-"sleep","unistd.h","!defined(CONFIG_DISABLE_SIGNALS)","unsigned int","unsigned int"
-"socket","sys/socket.h","CONFIG_NSOCKET_DESCRIPTORS > 0 && defined(CONFIG_NET)","int","int","int","int"
-"stat","sys/stat.h","CONFIG_NFILE_DESCRIPTORS > 0","int","const char*","FAR struct stat*"
-#"statfs","stdio.h","","int","FAR const char*","FAR struct statfs*"
-"statfs","sys/statfs.h","CONFIG_NFILE_DESCRIPTORS > 0","int","const char*","struct statfs*"
-"task_create","sched.h","","int","const char*","int","int","main_t","const char* []|const char**"
-#"task_create","sched.h","","int","const char*","int","main_t","const char* []|const char**"
-"task_delete","sched.h","","int","pid_t"
-"task_restart","sched.h","","int","pid_t"
-"telldir","dirent.h","CONFIG_NFILE_DESCRIPTORS > 0","off_t","FAR DIR*"
-"timer_create","time.h","!defined(CONFIG_DISABLE_POSIX_TIMERS)","int","clockid_t","FAR struct sigevent*","FAR timer_t*"
-"timer_delete","time.h","!defined(CONFIG_DISABLE_POSIX_TIMERS)","int","timer_t"
-"timer_getoverrun","time.h","!defined(CONFIG_DISABLE_POSIX_TIMERS)","int","timer_t"
-"timer_gettime","time.h","!defined(CONFIG_DISABLE_POSIX_TIMERS)","int","timer_t","FAR struct itimerspec*"
-"timer_settime","time.h","!defined(CONFIG_DISABLE_POSIX_TIMERS)","int","timer_t","int","FAR const struct itimerspec*","FAR struct itimerspec*"
-"umount","sys/mount.h","CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_DISABLE_MOUNTPOINT)","int","const char*"
-"unlink","unistd.h","CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_DISABLE_MOUNTPOINT)","int","FAR const char*"
-"unsetenv","stdlib.h","!defined(CONFIG_DISABLE_ENVIRON)","int","const char*"
-"up_assert","assert.h","","void","FAR const uint8_t*","int"
-#"up_assert","assert.h","","void"
-"up_assert_code","assert.h","","void","FAR const uint8_t*","int","int"
-#"up_assert_code","assert.h","","void","int"
-"usleep","unistd.h","!defined(CONFIG_DISABLE_SIGNALS)","int","useconds_t"
-#"wait","sys/wait.h","","pid_t","int*"
-#"waitid","sys/wait.h","","int","idtype_t","id_t id","siginfo_t*","int"
-"waitpid","sys/wait.h","defined(CONFIG_SCHED_WAITPID)","pid_t","pid_t","int*","int"
-"write","unistd.h","CONFIG_NSOCKET_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0","ssize_t","int","FAR const void*","size_t"