summaryrefslogtreecommitdiff
path: root/nuttx/syscall
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-03-06 19:56:32 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-03-06 19:56:32 +0000
commit7c2ea5a1a560284b6d22a60d62ac943ec6144096 (patch)
tree8d1191e3b5fe5cb9f0fe1319d45648d859060cae /nuttx/syscall
parent9e9de3d19ebf1890bfccd0bf63fa0209e2ec9359 (diff)
downloadpx4-nuttx-7c2ea5a1a560284b6d22a60d62ac943ec6144096.tar.gz
px4-nuttx-7c2ea5a1a560284b6d22a60d62ac943ec6144096.tar.bz2
px4-nuttx-7c2ea5a1a560284b6d22a60d62ac943ec6144096.zip
Fix some bad syscall dispatching log. This change is not testable until these is a tested NuttX kernel build.
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5713 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/syscall')
-rw-r--r--nuttx/syscall/Makefile16
-rw-r--r--nuttx/syscall/stub_lookup.c272
-rw-r--r--nuttx/syscall/stub_lookup.h268
-rw-r--r--nuttx/syscall/syscall.csv15
-rw-r--r--nuttx/syscall/syscall_funclookup.c108
-rw-r--r--nuttx/syscall/syscall_lookup.h290
-rw-r--r--nuttx/syscall/syscall_nparms.c78
-rw-r--r--nuttx/syscall/syscall_stublookup.c343
8 files changed, 836 insertions, 554 deletions
diff --git a/nuttx/syscall/Makefile b/nuttx/syscall/Makefile
index 4556912be..eb602624e 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-2013 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
@@ -9,14 +9,14 @@
# are met:
#
# 1. Redistributions of source code must retain the above copyright
-# notice, this list of conditions and the following disclaimer.
+# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
-# notice, this list of conditions and the following disclaimer in
-# the documentation and/or other materials provided with the
-# distribution.
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
# 3. Neither the name NuttX nor the names of its contributors may be
-# used to endorse or promote products derived from this software
-# without specific prior written permission.
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
@@ -42,7 +42,7 @@ include stubs$(DELIM)Make.defs
MKSYSCALL = "$(TOPDIR)$(DELIM)tools$(DELIM)mksyscall$(EXEEXT)"
CSVFILE = "$(TOPDIR)$(DELIM)syscall$(DELIM)syscall.csv"
-STUB_SRCS += stub_lookup.c
+STUB_SRCS += syscall_funclookup.c syscall_stublookup.c syscall_nparms.c
ASRCS =
AOBJS = $(ASRCS:.S=$(OBJEXT))
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/syscall.csv b/nuttx/syscall/syscall.csv
index 5f68697ca..988589ad2 100644
--- a/nuttx/syscall/syscall.csv
+++ b/nuttx/syscall/syscall.csv
@@ -6,11 +6,14 @@
"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*"
+"clock_systimer","nuttx/clock.h","!defined(CONFIG_DISABLE_CLOCK)","uint32_t"
"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"
+"execl","unistd.h","!defined(CONFIG_BINFMT_DISABLE) && defined(CONFIG_LIBC_EXECFUNCS)","int","FAR const char *path","..."
+"execv","unistd.h","!defined(CONFIG_BINFMT_DISABLE) && defined(CONFIG_LIBC_EXECFUNCS)","int","FAR const char *path","FAR char *const argv[]"
"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 struct tcb_s*"
@@ -40,11 +43,10 @@
"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","spawn.h","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","spawn.h","!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 []"
+"prctl","sys/prctl.h", "CONFIG_TASK_NAME_SIZE > 0","int","int","..."
+"posix_spawnp","spawn.h","!defined(CONFIG_BINFMT_DISABLE) && defined(CONFIG_LIBC_EXECFUNCS) && 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","spawn.h","!defined(CONFIG_BINFMT_DISABLE) && defined(CONFIG_LIBC_EXECFUNCS) && !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*"
@@ -138,7 +140,8 @@
"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"
+"vfork","unistd.h","defined(CONFIG_ARCH_HAVE_VFORK)","pid_t"
+"wait","sys/wait.h","defined(CONFIG_SCHED_WAITPID) && defined(CONFIG_SCHED_HAVE_PARENT)","pid_t","int*"
+"waitid","sys/wait.h","defined(CONFIG_SCHED_WAITPID) && defined(CONFIG_SCHED_HAVE_PARENT)","int","idtype_t","id_t"," FAR 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"
diff --git a/nuttx/syscall/syscall_funclookup.c b/nuttx/syscall/syscall_funclookup.c
new file mode 100644
index 000000000..e127dc5c9
--- /dev/null
+++ b/nuttx/syscall/syscall_funclookup.c
@@ -0,0 +1,108 @@
+/****************************************************************************
+ * syscall/syscall_funclookup.c
+ *
+ * Copyright (C) 2011-2013 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>
+
+/* The content of this file is only meaningful during the kernel phase of
+ * a kernel build.
+ */
+
+#if defined(CONFIG_NUTTX_KERNEL) && defined(__KERNEL__)
+
+#include <sys/stat.h>
+#include <sys/wait.h>
+#include <sys/ioctl.h>
+#include <sys/select.h>
+#include <sys/mman.h>
+#include <sys/stat.h>
+#include <sys/statfs.h>
+#include <sys/prctl.h>
+#include <sys/socket.h>
+#include <sys/mount.h>
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <dirent.h>
+#include <poll.h>
+#include <time.h>
+#include <sched.h>
+#include <pthread.h>
+#include <semaphore.h>
+#include <signal.h>
+#include <mqueue.h>
+#include <spawn.h>
+#include <assert.h>
+#include <errno.h>
+
+/****************************************************************************
+ * Pre-processor definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/* Function lookup tables. This table is indexed by the system call numbers
+ * defined above. Given the system call number, this table provides the
+ * address of the corresponding system function.
+ *
+ * This table is only available during the kernel phase of a kernel build.
+ */
+
+const uintptr_t g_funclookup[SYS_nsyscalls] =
+{
+# undef SYSCALL_LOOKUP1
+# define SYSCALL_LOOKUP1(f,n,p) (uintptr_t)f
+# undef SYSCALL_LOOKUP
+# define SYSCALL_LOOKUP(f,n,p) , (uintptr_t)f
+# include "syscall_lookup.h"
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+#endif /* CONFIG_NUTTX_KERNEL && __KERNEL__ */
diff --git a/nuttx/syscall/syscall_lookup.h b/nuttx/syscall/syscall_lookup.h
new file mode 100644
index 000000000..928194642
--- /dev/null
+++ b/nuttx/syscall/syscall_lookup.h
@@ -0,0 +1,290 @@
+/****************************************************************************
+ * syscall/syscall_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
+ ****************************************************************************/
+
+/* SYSCALL_LOOKUP must be defined before including this file.
+ *
+ * These first system calls are supported regardless of the NuttX
+ * configuration
+ */
+
+SYSCALL_LOOKUP1(_exit, 1, STUB__exit)
+SYSCALL_LOOKUP(exit, 1, STUB_exit)
+SYSCALL_LOOKUP(get_errno, 0, STUB_get_errno)
+SYSCALL_LOOKUP(getpid, 0, STUB_getpid)
+SYSCALL_LOOKUP(sched_getparam, 2, STUB_sched_getparam)
+SYSCALL_LOOKUP(sched_getscheduler, 1, STUB_sched_getscheduler)
+SYSCALL_LOOKUP(sched_lock, 0, STUB_sched_lock)
+SYSCALL_LOOKUP(sched_lockcount, 0, STUB_sched_lockcount)
+SYSCALL_LOOKUP(sched_rr_get_interval, 2, STUB_sched_rr_get_interval)
+SYSCALL_LOOKUP(sched_setparam, 2, STUB_sched_setparam)
+SYSCALL_LOOKUP(sched_setscheduler, 3, STUB_sched_setscheduler)
+SYSCALL_LOOKUP(sched_unlock, 0, STUB_sched_unlock)
+SYSCALL_LOOKUP(sched_yield, 0, STUB_sched_yield)
+SYSCALL_LOOKUP(sem_close, 1, STUB_sem_close)
+SYSCALL_LOOKUP(sem_destroy, 2, STUB_sem_destroy)
+SYSCALL_LOOKUP(sem_open, 6, STUB_sem_open)
+SYSCALL_LOOKUP(sem_post, 1, STUB_sem_post)
+SYSCALL_LOOKUP(sem_trywait, 1, STUB_sem_trywait)
+SYSCALL_LOOKUP(sem_unlink, 1, STUB_sem_unlink)
+SYSCALL_LOOKUP(sem_wait, 1, STUB_sem_wait)
+SYSCALL_LOOKUP(set_errno, 1, STUB_set_errno)
+SYSCALL_LOOKUP(task_create, 5, STUB_task_create)
+SYSCALL_LOOKUP(task_delete, 1, STUB_task_delete)
+SYSCALL_LOOKUP(task_restart, 1, STUB_task_restart)
+SYSCALL_LOOKUP(up_assert, 2, STUB_up_assert)
+SYSCALL_LOOKUP(up_assert_code, 3, STUB_up_assert_code)
+
+/* The following can be individually enabled */
+
+#ifdef CONFIG_ARCH_HAVE_VFORK
+ SYSCALL_LOOKUP(vfork, 0, SYS_vfork)
+#endif
+
+#ifdef CONFIG_SCHED_ATEXIT
+ SYSCALL_LOOKUP(atexit, 1, STUB_atexit)
+#endif
+
+#ifdef CONFIG_SCHED_ONEXIT
+ SYSCALL_LOOKUP(on_exit, 2, STUB_onexit)
+#endif
+
+#ifdef CONFIG_SCHED_WAITPID
+ SYSCALL_LOOKUP(waitpid, 3, STUB_waitpid)
+# ifdef CONFIG_SCHED_HAVE_PARENT
+ SYSCALL_LOOKUP(wait, 1, STUB_wait)
+ SYSCALL_LOOKUP(waitid, 4, STUB_waitid)
+# endif
+#endif
+
+/* The following can only be defined if we are configured to execute
+ * programs from a file system.
+ */
+
+#if defined(CONFIG_BINFMT_DISABLE) && defined(CONFIG_LIBC_EXECFUNCS)
+# ifdef CONFIG_BINFMT_EXEPATH
+ SYSCALL_LOOKUP(posix_spawnp, 6, SYS_posixspawnp)
+# else
+ SYSCALL_LOOKUP(posix_spawn, 6, SYS_posixspawn)
+# endif
+ SYSCALL_LOOKUP(execv, 2, SYS_execv)
+ SYSCALL_LOOKUP(execl, 6, SYS_execl)
+#endif
+
+/* The following are only defined is signals are supported in the NuttX
+ * configuration.
+ */
+
+#ifndef CONFIG_DISABLE_SIGNALS
+ SYSCALL_LOOKUP(kill, 2, STUB_kill)
+ SYSCALL_LOOKUP(sigaction, 3, STUB_sigaction)
+ SYSCALL_LOOKUP(sigpending, 1, STUB_sigpending)
+ SYSCALL_LOOKUP(sigprocmask, 3, STUB_sigprocmask)
+ SYSCALL_LOOKUP(sigqueue, 3, STUB_sigqueue)
+ SYSCALL_LOOKUP(sigsuspend, 1, STUB_sigsuspend)
+ SYSCALL_LOOKUP(sigtimedwait, 3, STUB_sigtimedwait)
+ SYSCALL_LOOKUP(sigwaitinfo, 2, STUB_sigwaitinfo)
+ SYSCALL_LOOKUP(sleep, 1, STUB_sleep)
+ SYSCALL_LOOKUP(usleep, 1, STUB_usleep)
+#endif
+
+/* The following are only defined if the system clock is enabled in the
+ * NuttX configuration.
+ */
+
+#ifndef CONFIG_DISABLE_CLOCK
+ SYSCALL_LOOKUP(clock_systimer, 0, STUB_clock_systimer)
+ SYSCALL_LOOKUP(clock_getres, 2, STUB_clock_getres)
+ SYSCALL_LOOKUP(clock_gettime, 2, STUB_clock_gettime)
+ SYSCALL_LOOKUP(clock_settime, 2, STUB_clock_settime)
+ SYSCALL_LOOKUP(gettimeofday, 2, STUB_gettimeofday)
+#endif
+
+/* The following are defined only if POSIX timers are supported */
+
+#ifndef CONFIG_DISABLE_POSIX_TIMERS
+ SYSCALL_LOOKUP(timer_create, 3, STUB_timer_create)
+ SYSCALL_LOOKUP(timer_delete, 1, STUB_timer_delete)
+ SYSCALL_LOOKUP(timer_getoverrun, 1, STUB_timer_getoverrun)
+ SYSCALL_LOOKUP(timer_gettime, 2, STUB_timer_gettime)
+ SYSCALL_LOOKUP(timer_settime, 4, STUB_timer_settime)
+#endif
+
+/* The following are defined if either file or socket descriptor are
+ * enabled.
+ */
+
+#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
+ SYSCALL_LOOKUP(close, 1, STUB_close)
+ SYSCALL_LOOKUP(ioctl, 3, STUB_ioctl)
+ SYSCALL_LOOKUP(read, 3, STUB_read)
+ SYSCALL_LOOKUP(write, 3, STUB_write)
+# ifndef CONFIG_DISABLE_POLL
+ SYSCALL_LOOKUP(poll, 3, STUB_poll)
+ SYSCALL_LOOKUP(select, 5, STUB_select)
+# endif
+#endif
+
+/* The following are defined if file descriptors are enabled */
+
+#if CONFIG_NFILE_DESCRIPTORS > 0
+ SYSCALL_LOOKUP(closedir, 1, STUB_closedir)
+ SYSCALL_LOOKUP(dup, 1, STUB_dup)
+ SYSCALL_LOOKUP(dup2, 2, STUB_dup2)
+ SYSCALL_LOOKUP(fcntl, 6, STUB_fcntl)
+ SYSCALL_LOOKUP(lseek, 3, STUB_lseek)
+ SYSCALL_LOOKUP(mkfifo, 2, STUB_mkfifo)
+ SYSCALL_LOOKUP(mmap, 6, STUB_mmap)
+ SYSCALL_LOOKUP(open, 6, STUB_open)
+ SYSCALL_LOOKUP(opendir, 1, STUB_opendir)
+ SYSCALL_LOOKUP(pipe, 1, STUB_pipe)
+ SYSCALL_LOOKUP(readdir, 1, STUB_readdir)
+ SYSCALL_LOOKUP(rewinddir, 1, STUB_rewinddir)
+ SYSCALL_LOOKUP(seekdir, 2, STUB_seekdir)
+ SYSCALL_LOOKUP(stat, 2, STUB_stat)
+ SYSCALL_LOOKUP(statfs, 2, STUB_statfs)
+ SYSCALL_LOOKUP(telldir, 1, STUB_telldir)
+
+# if CONFIG_NFILE_STREAMS > 0
+ SYSCALL_LOOKUP(fdopen, 3, STUB_fs_fdopen)
+ SYSCALL_LOOKUP(sched_getstreams, 0, STUB_sched_getstreams)
+#endif
+
+# if !defined(CONFIG_DISABLE_MOUNTPOINT)
+ SYSCALL_LOOKUP(fsync, 1, STUB_fsync)
+ SYSCALL_LOOKUP(mkdir, 2, STUB_mkdir)
+ SYSCALL_LOOKUP(mount, 5, STUB_mount)
+ SYSCALL_LOOKUP(rename, 2, STUB_rename)
+ SYSCALL_LOOKUP(rmdir, 1, STUB_rmdir)
+ SYSCALL_LOOKUP(umount, 1, STUB_umount)
+ SYSCALL_LOOKUP(unlink 1, STUB_unlink)
+# endif
+#endif
+
+/* The following are defined if pthreads are enabled */
+
+#ifndef CONFIG_DISABLE_PTHREAD
+ SYSCALL_LOOKUP(pthread_barrier_destroy, 1, STUB_pthread_barrier_destroy)
+ SYSCALL_LOOKUP(pthread_barrier_init, 3, STUB_pthread_barrier_init)
+ SYSCALL_LOOKUP(pthread_barrier_wait, 1, STUB_pthread_barrier_wait)
+ SYSCALL_LOOKUP(pthread_cancel, 1, STUB_pthread_cancel)
+ SYSCALL_LOOKUP(pthread_cond_broadcast, 1, STUB_pthread_cond_broadcast)
+ SYSCALL_LOOKUP(pthread_cond_destroy, 1, STUB_pthread_cond_destroy)
+ SYSCALL_LOOKUP(pthread_cond_init, 2, STUB_pthread_cond_init)
+ SYSCALL_LOOKUP(pthread_cond_signal, 1, STUB_pthread_cond_signal)
+ SYSCALL_LOOKUP(pthread_cond_wait, 2, STUB_pthread_cond_wait)
+ SYSCALL_LOOKUP(pthread_create, 4, STUB_pthread_create)
+ SYSCALL_LOOKUP(pthread_detach, 1, STUB_pthread_detach)
+ SYSCALL_LOOKUP(pthread_exit, 1, STUB_pthread_exit)
+ SYSCALL_LOOKUP(pthread_getschedparam, 3, STUB_pthread_getschedparam)
+ SYSCALL_LOOKUP(pthread_getspecific, 1, STUB_pthread_getspecific)
+ SYSCALL_LOOKUP(pthread_join, 2, STUB_pthread_join)
+ SYSCALL_LOOKUP(pthread_key_create, 2, STUB_pthread_key_create)
+ SYSCALL_LOOKUP(pthread_key_delete, 1, STUB_pthread_key_delete)
+ SYSCALL_LOOKUP(pthread_mutex_destroy, 1, STUB_pthread_mutex_destroy)
+ SYSCALL_LOOKUP(pthread_mutex_init, 2, STUB_pthread_mutex_init)
+ SYSCALL_LOOKUP(pthread_mutex_lock, 1, STUB_pthread_mutex_lock)
+ SYSCALL_LOOKUP(pthread_mutex_trylock, 1, STUB_pthread_mutex_trylock)
+ SYSCALL_LOOKUP(pthread_mutex_unlock, 1, STUB_pthread_mutex_unlock)
+ SYSCALL_LOOKUP(pthread_once, 2, STUB_pthread_once)
+ SYSCALL_LOOKUP(pthread_setcancelstate, 2, STUB_pthread_setcancelstate)
+ SYSCALL_LOOKUP(pthread_setschedparam, 3, STUB_pthread_setschedparam)
+ SYSCALL_LOOKUP(pthread_setschedprio, 2, STUB_pthread_setschedprio)
+ SYSCALL_LOOKUP(pthread_setspecific, 2, STUB_pthread_setspecific)
+ SYSCALL_LOOKUP(pthread_yield, 0, STUB_pthread_yield)
+# ifndef CONFIG_DISABLE_SIGNAL
+ SYSCALL_LOOKUP(pthread_cond_timedwait, 3, STUB_pthread_cond_timedwait)
+ SYSCALL_LOOKUP(pthread_kill, 2, STUB_pthread_kill)
+ SYSCALL_LOOKUP(pthread_sigmask, 3, STUB_pthread_sigmask)
+# endif
+#endif
+
+/* The following are defined only if message queues are enabled */
+
+#ifndef CONFIG_DISABLE_MQUEUE
+ SYSCALL_LOOKUP(mq_close, 1, STUB_mq_close)
+ SYSCALL_LOOKUP(mq_notify, 2, STUB_mq_notify)
+ SYSCALL_LOOKUP(mq_open, 6, STUB_mq_open)
+ SYSCALL_LOOKUP(mq_receive, 4, STUB_mq_receive)
+ SYSCALL_LOOKUP(mq_send, 4, STUB_mq_send)
+ SYSCALL_LOOKUP(mq_timedreceive, 5, STUB_mq_timedreceive)
+ SYSCALL_LOOKUP(mq_timedsend, 5, STUB_mq_timedsend)
+ SYSCALL_LOOKUP(mq_unlink, 1, STUB_mq_unlink)
+#endif
+
+/* The following are defined only if environment variables are supported */
+
+#ifndef CONFIG_DISABLE_ENVIRON
+ SYSCALL_LOOKUP(clearenv, 0, STUB_clearenv)
+ SYSCALL_LOOKUP(getenv, 1, STUB_getenv)
+ SYSCALL_LOOKUP(putenv, 1, STUB_putenv)
+ SYSCALL_LOOKUP(setenv, 3, STUB_setenv)
+ SYSCALL_LOOKUP(unsetenv, 1, STUB_unsetenv)
+#endif
+
+/* The following are defined only if networking AND sockets are supported */
+
+#if CONFIG_NSOCKET_DESCRIPTORS > 0 && defined(CONFIG_NET)
+ SYSCALL_LOOKUP(accept, 3, STUB_accept)
+ SYSCALL_LOOKUP(bind, 3, STUB_bind)
+ SYSCALL_LOOKUP(connect, 3, STUB_connect)
+ SYSCALL_LOOKUP(getsockopt, 5, STUB_getsockopt)
+ SYSCALL_LOOKUP(listen, 2, STUB_listen)
+ SYSCALL_LOOKUP(recv, 4, STUB_recv)
+ SYSCALL_LOOKUP(recvfrom, 6, STUB_recvfrom)
+ SYSCALL_LOOKUP(send, 4, STUB_send)
+ SYSCALL_LOOKUP(sendto, 6, STUB_sendto)
+ SYSCALL_LOOKUP(setsockopt, 5, STUB_setsockopt)
+ SYSCALL_LOOKUP(socket, 3, STUB_socket)
+#endif
+
+/* The following is defined only if CONFIG_TASK_NAME_SIZE > 0 */
+
+#if CONFIG_TASK_NAME_SIZE > 0
+ SYSCALL_LOOKUP(prctl, 5, STUB_prctl)
+#endif
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+
diff --git a/nuttx/syscall/syscall_nparms.c b/nuttx/syscall/syscall_nparms.c
new file mode 100644
index 000000000..da417af7b
--- /dev/null
+++ b/nuttx/syscall/syscall_nparms.c
@@ -0,0 +1,78 @@
+/****************************************************************************
+ * 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>
+
+/* The content of this file is only meaning for the case of a kernel build. */
+
+#ifdef CONFIG_NUTTX_KERNEL
+
+/****************************************************************************
+ * Pre-processor definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/* Stub lookup tables. This table is indexed by the system call numbers
+ * defined above. Given the system call number, the corresponding entry in
+ * this table provides the number of parameters needed by the function.
+ */
+
+const uint8_t g_funcnparms[SYS_nsyscalls] =
+{
+# undef SYSCALL_LOOKUP1
+# define SYSCALL_LOOKUP1(f,n,p) n
+# undef SYSCALL_LOOKUP
+# define SYSCALL_LOOKUP(f,n,p) , n
+# include "syscall_lookup.h"
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+ #endif /* CONFIG_NUTTX_KERNEL */
+ \ No newline at end of file
diff --git a/nuttx/syscall/syscall_stublookup.c b/nuttx/syscall/syscall_stublookup.c
new file mode 100644
index 000000000..13eb57fc9
--- /dev/null
+++ b/nuttx/syscall/syscall_stublookup.c
@@ -0,0 +1,343 @@
+/****************************************************************************
+ * syscall/syscall_stublookup.c
+ *
+ * Copyright (C) 2011-2013 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>
+
+/* The content of this file is only meaningful during the kernel phase of
+ * a kernel build.
+ */
+
+#if defined(CONFIG_NUTTX_KERNEL) && defined(__KERNEL__)
+
+/****************************************************************************
+ * Pre-processor definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Stub Function Prototypes
+ ****************************************************************************/
+
+/* These first system calls are supported regardless of the NuttX
+ * configuration
+ */
+
+uintptr_t STUB__exit(int nbr, uintptr_t parm1);
+uintptr_t STUB_exit(int nbr, uintptr_t parm1);
+uintptr_t STUB_get_errno(int nbr);
+uintptr_t STUB_getpid(int nbr);
+uintptr_t STUB_sched_getparam(int nbr, uintptr_t parm1, uintptr_t parm2);
+uintptr_t STUB_sched_getscheduler(int nbr, uintptr_t parm1);
+uintptr_t STUB_sched_lock(int nbr);
+uintptr_t STUB_sched_lockcount(int nbr);
+uintptr_t STUB_sched_rr_get_interval(int nbr, uintptr_t parm1,
+ uintptr_t parm2);
+uintptr_t STUB_sched_setparam(int nbr, uintptr_t parm1, uintptr_t parm2);
+uintptr_t STUB_sched_setscheduler(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3);
+uintptr_t STUB_sched_unlock(int nbr);
+uintptr_t STUB_sched_yield(int nbr);
+uintptr_t STUB_sem_close(int nbr, uintptr_t parm1);
+uintptr_t STUB_sem_destroy(int nbr, uintptr_t parm1);
+uintptr_t STUB_sem_open(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3, uintptr_t parm4, uintptr_t parm5, uintptr_t parm6);
+uintptr_t STUB_sem_post(int nbr, uintptr_t parm1);
+uintptr_t STUB_sem_trywait(int nbr, uintptr_t parm1);
+uintptr_t STUB_sem_unlink(int nbr, uintptr_t parm1);
+uintptr_t STUB_sem_wait(int nbr, uintptr_t parm1);
+uintptr_t STUB_set_errno(int nbr, uintptr_t parm1);
+uintptr_t STUB_task_create(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3, uintptr_t parm4, uintptr_t parm5);
+uintptr_t STUB_task_delete(int nbr, uintptr_t parm1);
+uintptr_t STUB_task_restart(int nbr, uintptr_t parm1);
+uintptr_t STUB_up_assert(int nbr, uintptr_t parm1, uintptr_t parm2);
+uintptr_t STUB_up_assert_code(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3);
+
+/* The following can be individually enabled */
+
+uintptr_t STUB_vfork(int nbr);
+uintptr_t STUB_atexit(int nbr, uintptr_t parm1);
+uintptr_t STUB_on_exit(int nbr, uintptr_t parm1, uintptr_t parm2);
+uintptr_t STUB_waitpid(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3);
+uintptr_t STUB_wait(int nbr, uintptr_t parm1);
+uintptr_t STUB_waitid(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3, uintptr_t parm4);
+
+/* The following can only be defined if we are configured to execute
+ * programs from a file system.
+ */
+
+uintptr_t STUB_posix_spawn(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3, uintptr_t parm4, uintptr_t parm5,
+ uintptr_t parm6);
+uintptr_t STUB_posix_spawnp(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3, uintptr_t parm4, uintptr_t parm6,
+ uintptr_t parm6);
+uintptr_t STUB_execv(int nbr, uintptr_t parm1, uintptr_t parm2);
+uintptr_t STUB_execl(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3, uintptr_t parm4, uintptr_t parm5,
+ uintptr_t parm6);
+
+/* The following are only defined is signals are supported in the NuttX
+ * configuration.
+ */
+
+uintptr_t STUB_kill(int nbr, uintptr_t parm1, uintptr_t parm2);
+uintptr_t STUB_sigaction(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3);
+uintptr_t STUB_sigpending(int nbr, uintptr_t parm1);
+uintptr_t STUB_sigprocmask(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3);
+uintptr_t STUB_sigqueue(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3);
+uintptr_t STUB_sigsuspend(int nbr, uintptr_t parm1);
+uintptr_t STUB_sigtimedwait(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3);
+uintptr_t STUB_sigwaitinfo(int nbr, uintptr_t parm1, uintptr_t parm2);
+uintptr_t STUB_sleep(int nbr, uintptr_t parm1);
+uintptr_t STUB_usleep(int nbr, uintptr_t parm1);
+
+/* The following are only defined if the system clock is enabled in the
+ * NuttX configuration.
+ */
+
+uintptr_t STUB_clock_systimer(int nbr);
+uintptr_t STUB_clock_getres(int nbr, uintptr_t parm1, uintptr_t parm2);
+uintptr_t STUB_clock_gettime(int nbr, uintptr_t parm1, uintptr_t parm2);
+uintptr_t STUB_clock_settime(int nbr, uintptr_t parm1, uintptr_t parm2);
+uintptr_t STUB_gettimeofday(int nbr, uintptr_t parm1, uintptr_t parm2);
+
+/* The following are defined only if POSIX timers are supported */
+
+uintptr_t STUB_timer_create(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3);
+uintptr_t STUB_timer_delete(int nbr, uintptr_t parm1);
+uintptr_t STUB_timer_getoverrun(int nbr, uintptr_t parm1);
+uintptr_t STUB_timer_gettime(int nbr, uintptr_t parm1, uintptr_t parm2);
+uintptr_t STUB_timer_settime(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3, uintptr_t parm4);
+
+/* The following are defined if either file or socket descriptor are
+ * enabled.
+ */
+
+uintptr_t STUB_close(int nbr, uintptr_t parm1);
+uintptr_t STUB_ioctl(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3);
+uintptr_t STUB_poll(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3);
+uintptr_t STUB_read(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3);
+uintptr_t STUB_select(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3, uintptr_t parm4, uintptr_t parm5);
+uintptr_t STUB_write(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3);
+
+/* The following are defined if file descriptors are enabled */
+
+uintptr_t STUB_closedir(int nbr, uintptr_t parm1);
+uintptr_t STUB_dup(int nbr, uintptr_t parm1);
+uintptr_t STUB_dup2(int nbr, uintptr_t parm1, uintptr_t parm2);
+uintptr_t STUB_fcntl(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3, uintptr_t parm4, uintptr_t parm5,
+ uintptr_t parm6);
+uintptr_t STUB_lseek(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3);
+uintptr_t STUB_mkfifo(int nbr, uintptr_t parm1, uintptr_t parm2);
+uintptr_t STUB_mmap(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3, uintptr_t parm4, uintptr_t parm5,
+ uintptr_t parm6);
+uintptr_t STUB_open(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3, uintptr_t parm4, uintptr_t parm5,
+ uintptr_t parm6);
+uintptr_t STUB_opendir(int nbr, uintptr_t parm1);
+uintptr_t STUB_pipe(int nbr, uintptr_t parm1);
+uintptr_t STUB_readdir(int nbr, uintptr_t parm1);
+uintptr_t STUB_rewinddir(int nbr, uintptr_t parm1);
+uintptr_t STUB_seekdir(int nbr, uintptr_t parm1, uintptr_t parm2);
+uintptr_t STUB_stat(int nbr, uintptr_t parm1, uintptr_t parm2);
+uintptr_t STUB_statfs(int nbr, uintptr_t parm1, uintptr_t parm2);
+uintptr_t STUB_telldir(int nbr, uintptr_t parm1);
+
+uintptr_t STUB_fs_fdopen(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3);
+uintptr_t STUB_sched_getstreams(int nbr);
+
+uintptr_t STUB_fsync(int nbr, uintptr_t parm1);
+uintptr_t STUB_mkdir(int nbr, uintptr_t parm1, uintptr_t parm2);
+uintptr_t STUB_mount(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3, uintptr_t parm4, uintptr_t parm5);
+uintptr_t STUB_rename(int nbr, uintptr_t parm1, uintptr_t parm2);
+uintptr_t STUB_rmdir(int nbr, uintptr_t parm1);
+uintptr_t STUB_umount(int nbr, uintptr_t parm1);
+uintptr_t STUB_unlink(int nbr, uintptr_t parm1);
+
+/* The following are defined if pthreads are enabled */
+
+uintptr_t STUB_pthread_barrier_destroy(int nbr, uintptr_t parm1);
+uintptr_t STUB_pthread_barrier_init(int nbr, uintptr_t parm1,
+ uintptr_t parm2, uintptr_t parm3);
+uintptr_t STUB_pthread_barrier_wait(int nbr, uintptr_t parm1);
+uintptr_t STUB_pthread_cancel(int nbr, uintptr_t parm1);
+uintptr_t STUB_pthread_cond_broadcast(int nbr, uintptr_t parm1);
+uintptr_t STUB_pthread_cond_destroy(int nbr, uintptr_t parm1);
+uintptr_t STUB_pthread_cond_init(int nbr, uintptr_t parm1, uintptr_t parm2);
+uintptr_t STUB_pthread_cond_signal(int nbr, uintptr_t parm1);
+uintptr_t STUB_pthread_cond_wait(int nbr, uintptr_t parm1, uintptr_t parm2);
+uintptr_t STUB_pthread_create(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3, uintptr_t parm4);
+uintptr_t STUB_pthread_detach(int nbr, uintptr_t parm1);
+uintptr_t STUB_pthread_exit(int nbr, uintptr_t parm1);
+uintptr_t STUB_pthread_getschedparam(int nbr, uintptr_t parm1,
+ uintptr_t parm2, uintptr_t parm3);
+uintptr_t STUB_pthread_getspecific(int nbr, uintptr_t parm1);
+uintptr_t STUB_pthread_join(int nbr, uintptr_t parm1, uintptr_t parm2);
+uintptr_t STUB_pthread_key_create(int nbr, uintptr_t parm1,
+ uintptr_t parm2);
+uintptr_t STUB_pthread_key_delete(int nbr, uintptr_t parm1);
+uintptr_t STUB_pthread_mutex_destroy(int nbr, uintptr_t parm1);
+uintptr_t STUB_pthread_mutex_init(int nbr, uintptr_t parm1,
+ uintptr_t parm2);
+uintptr_t STUB_pthread_mutex_lock(int nbr, uintptr_t parm1);
+uintptr_t STUB_pthread_mutex_trylock(int nbr, uintptr_t parm1);
+uintptr_t STUB_pthread_mutex_unlock(int nbr, uintptr_t parm1);
+uintptr_t STUB_pthread_once(int nbr, uintptr_t parm1, uintptr_t parm2);
+uintptr_t STUB_pthread_setcancelstate(int nbr, uintptr_t parm1,
+ uintptr_t parm2);
+uintptr_t STUB_pthread_setschedparam(int nbr, uintptr_t parm1,
+ uintptr_t parm2, uintptr_t parm3);
+uintptr_t STUB_pthread_setschedprio(int nbr, uintptr_t parm1,
+ uintptr_t parm2);
+uintptr_t STUB_pthread_setspecific(int nbr, uintptr_t parm1,
+ uintptr_t parm2);
+uintptr_t STUB_pthread_yield(int nbr);
+
+uintptr_t STUB_pthread_cond_timedwait(int nbr, uintptr_t parm1,
+ uintptr_t parm2, uintptr_t parm3);
+uintptr_t STUB_pthread_kill(int nbr, uintptr_t parm1, uintptr_t parm2);
+uintptr_t STUB_pthread_sigmask(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3);
+
+/* The following are defined only if message queues are enabled */
+
+uintptr_t STUB_mq_close(int nbr, uintptr_t parm1);
+uintptr_t STUB_mq_notify(int nbr, uintptr_t parm1, uintptr_t parm2);
+uintptr_t STUB_mq_open(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3, uintptr_t parm4, uintptr_t parm5,
+ uintptr_t parm6);
+uintptr_t STUB_mq_receive(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3, uintptr_t parm4);
+uintptr_t STUB_mq_send(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3, uintptr_t parm4);
+uintptr_t STUB_mq_timedreceive(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3, uintptr_t parm4, uintptr_t parm5);
+uintptr_t STUB_mq_timedsend(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3, uintptr_t parm4, uintptr_t parm5);
+uintptr_t STUB_mq_unlink(int nbr, uintptr_t parm1);
+
+/* The following are defined only if environment variables are supported */
+
+uintptr_t STUB_clearenv(int nbr);
+uintptr_t STUB_getenv(int nbr, uintptr_t parm1);
+uintptr_t STUB_putenv(int nbr, uintptr_t parm1);
+uintptr_t STUB_setenv(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3);
+uintptr_t STUB_unsetenv(int nbr, uintptr_t parm1);
+
+/* The following are defined only if networking AND sockets are supported */
+
+uintptr_t STUB_accept(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3);
+uintptr_t STUB_bind(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3);
+uintptr_t STUB_connect(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3);
+uintptr_t STUB_getsockopt(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3, uintptr_t parm4, uintptr_t parm5);
+uintptr_t STUB_listen(int nbr, uintptr_t parm1, uintptr_t parm2);
+uintptr_t STUB_recv(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3, uintptr_t parm4);
+uintptr_t STUB_recvfrom(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3, uintptr_t parm4, uintptr_t parm5,
+ uintptr_t parm6);
+uintptr_t STUB_send(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3, uintptr_t parm4);
+uintptr_t STUB_sendto(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3, uintptr_t parm4, uintptr_t parm5,
+ uintptr_t parm6);
+uintptr_t STUB_setsockopt(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3, uintptr_t parm4, uintptr_t parm5);
+uintptr_t STUB_socket(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3);
+
+/* The following is defined only if CONFIG_TASK_NAME_SIZE > 0 */
+
+uintptr_t STUB_prctl(int nbr, uintptr_t parm1, uintptr_t parm2,
+ uintptr_t parm3, uintptr_t parm4, uintptr_t parm5);
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/* Stub lookup tables. This table is indexed by the system call number.
+ * Given the system call number, the corresponding entry in this table
+ * provides the address of the stub function.
+ */
+
+const uintptr_t g_stublookup[SYS_nsyscalls] =
+{
+# undef SYSCALL_LOOKUP1
+# define SYSCALL_LOOKUP1(f,n,p) (uintptr_t)p
+# undef SYSCALL_LOOKUP
+# define SYSCALL_LOOKUP(f,n,p) , (uintptr_t)p
+# include "syscall_lookup.h"
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+#endif /* CONFIG_NUTTX_KERNEL && __KERNEL__ */
+