aboutsummaryrefslogtreecommitdiff
path: root/nuttx/libc
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-01-08 16:25:30 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-01-08 16:25:30 +0000
commit14f72f7a210648fe6eaaac3359ec76cab62c7278 (patch)
treebe370af4ffb6147bbbf103f66fcc69ed55bf5893 /nuttx/libc
parent3d160e45b64485aa5f231179bf61cdea8fc5c141 (diff)
downloadpx4-firmware-14f72f7a210648fe6eaaac3359ec76cab62c7278.tar.gz
px4-firmware-14f72f7a210648fe6eaaac3359ec76cab62c7278.tar.bz2
px4-firmware-14f72f7a210648fe6eaaac3359ec76cab62c7278.zip
Add execv() and execl(); Move lm3s header files for compatibility
git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5492 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/libc')
-rw-r--r--nuttx/libc/Kconfig48
-rw-r--r--nuttx/libc/unistd/Make.defs4
-rw-r--r--nuttx/libc/unistd/lib_execl.c146
-rw-r--r--nuttx/libc/unistd/lib_execv.c168
4 files changed, 366 insertions, 0 deletions
diff --git a/nuttx/libc/Kconfig b/nuttx/libc/Kconfig
index 0ae56ac57..699b3ebb2 100644
--- a/nuttx/libc/Kconfig
+++ b/nuttx/libc/Kconfig
@@ -71,6 +71,54 @@ config EOL_IS_EITHER_CRLF
endchoice
+config LIBC_EXECFUNCS
+ bool "Enable exec[l|v] Support"
+ default n
+ depends on !BINFMT_DISABLE
+ ---help---
+ Enable support for the exec[l|v] family of functions that can be
+ used to start other programs, terminating the current program.
+ Typical usage is (1) first call vfork() to create a new thread, then
+ (2) call exec[l|v] to replace the new thread with a program from the
+ file system.
+
+ NOTE 1: This two step process start is completely unnecessary in
+ NuttX and is provided only for compatibily with Unix systems. These
+ functions are essentially just wrapper functions that (1) call the
+ non-standard binfmt function 'exec', and then (2) exit(0). Since
+ the new thread will be terminated by the exec[l|v] call, it really
+ served no purpose other than to suport Unix compatility.
+
+ NOTE 2: Support for exec[l|v] is conditional because is requires
+ additional support for symbol tables that will not be available in
+ the typical system.
+
+if LIBC_EXECFUNCS
+
+config EXECFUNCS_SYMTAB
+ string "Symbol table used by exec[l|v]"
+ default "g_symtab"
+ ---help---
+ The exec[l|v] functions are wrapper functions that (1) call the non-
+ standard binfmt function 'exec', and then (2) exit(0). The binfmt
+ function 'exec' needs to have (1) a symbol table that provides the
+ list of symbols exported by the base code, and (2) the number of
+ symbols in that table. This selection provides the name of that
+ symbol table.
+
+config EXECFUNCS_NSYMBOLS
+ int "Number of Symbols in the Table"
+ default 0
+ ---help---
+ The exec[l|v] functions are wrapper functions that (1) call the non-
+ standard binfmt function 'exec', and then (2) exit(0). The binfmt
+ function 'exec' needs to have (1) a symbol table that provides the
+ list of symbols exported by the base code, and (2) the number of
+ symbols in that table. This selection provides the number of
+ symbols in the symbol table.
+
+endif
+
config LIBC_STRERROR
bool "Enable strerror"
default n
diff --git a/nuttx/libc/unistd/Make.defs b/nuttx/libc/unistd/Make.defs
index 67fce9b1d..3811673bf 100644
--- a/nuttx/libc/unistd/Make.defs
+++ b/nuttx/libc/unistd/Make.defs
@@ -41,6 +41,10 @@ ifneq ($(CONFIG_NFILE_DESCRIPTORS),0)
ifneq ($(CONFIG_DISABLE_ENVIRON),y)
CSRCS += lib_chdir.c lib_getcwd.c
endif
+
+ifeq ($(CONFIG_LIBC_EXECFUNCS),y)
+CSRCS += lib_execl.c lib_execv.c
+endif
endif
# Add the unistd directory to the build
diff --git a/nuttx/libc/unistd/lib_execl.c b/nuttx/libc/unistd/lib_execl.c
new file mode 100644
index 000000000..ac3147343
--- /dev/null
+++ b/nuttx/libc/unistd/lib_execl.c
@@ -0,0 +1,146 @@
+/****************************************************************************
+ * libc/unistd/lib_execl.c
+ *
+ * Copyright (C) 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 <stdarg.h>
+#include <unistd.h>
+
+#ifdef CONFIG_LIBC_EXECFUNCS
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: execl
+ *
+ * Description:
+ * The standard 'exec' family of functions will replace the current process
+ * image with a new process image. The new image will be constructed from a
+ * regular, executable file called the new process image file. There will
+ * be no return from a successful exec, because the calling process image
+ * is overlaid by the new process image.
+ *
+ * Simplified 'execl()' and 'execv()' functions are provided by NuttX for
+ * compatibility. NuttX is a tiny embedded RTOS that does not support
+ * processes and hence the concept of overlaying a tasks process image with
+ * a new process image does not make any sense. In NuttX, these functions
+ * are wrapper functions that:
+ *
+ * 1. Call the non-standard binfmt function 'exec', and then
+ * 2. exit(0).
+ *
+ * Note the inefficiency when 'exec[l|v]()' is called in the normal, two-
+ * step process: (1) first call vfork() to create a new thread, then (2)
+ * call 'exec[l|v]()' to replace the new thread with a program from the
+ * file system. Since the new thread will be terminated by the
+ * 'exec[l|v]()' call, it really served no purpose other than to suport
+ * Unix compatility.
+ *
+ * The non-standard binfmt function 'exec()' needs to have (1) a symbol
+ * table that provides the list of symbols exported by the base code, and
+ * (2) the number of symbols in that table. This information is currently
+ * provided to 'exec()' from 'exec[l|v]()' via NuttX configuration settings:
+ *
+ * CONFIG_LIBC_EXECFUNCS : Enable exec[l|v] Support
+ * CONFIG_EXECFUNCS_SYMTAB : Symbol table used by exec[l|v]
+ * CONFIG_EXECFUNCS_NSYMBOLS : Number of Symbols in the Table
+ *
+ * As a result of the above, the current implementations of 'execl()' and
+ * 'execv()' suffer from some incompatibilities that may or may not be
+ * addressed in a future version of NuttX. Other than just being an
+ * inefficient use of MCU resource, the most serious of these is that
+ * the exec'ed task will not have the same task ID as the vfork'ed
+ * function. So the parent function cannot know the ID of the exec'ed
+ * task.
+ *
+ * Input Parameters:
+ * path - The path to the program to be executed. If CONFIG_BINFMT_EXEPATH
+ * is defined in the configuration, then this may be a relative path
+ * from the current working directory. Otherwise, path must be the
+ * absolute path to the program.
+ * arg0,... - A list of the string arguments to be recevied by the
+ * program. Zero indicates the end of the list.
+ *
+ * Returned Value:
+ * This function does not return on success. On failure, it will return
+ * -1 (ERROR) and will set the 'errno' value appropriately.
+ *
+ ****************************************************************************/
+
+int execl(FAR const char *path, ...)
+{
+ FAR char *argv[CONFIG_MAX_TASK_ARGS+1];
+ va_list ap;
+ int argc;
+
+ /* Collect the arguments into the argv[] array */
+
+ va_start(ap, path);
+ for (argc = 0; argc < CONFIG_MAX_TASK_ARGS; argc++)
+ {
+ argv[argc] = va_arg(ap, FAR char *);
+ if (argv[argc] == NULL)
+ {
+ break;
+ }
+ }
+
+ argv[CONFIG_MAX_TASK_ARGS] = NULL;
+ va_end(ap);
+
+ /* Then let execv() do the real work */
+
+ return execv(path, (char * const *)&argv);
+}
+
+#endif /* CONFIG_LIBC_EXECFUNCS */ \ No newline at end of file
diff --git a/nuttx/libc/unistd/lib_execv.c b/nuttx/libc/unistd/lib_execv.c
new file mode 100644
index 000000000..cad8ee307
--- /dev/null
+++ b/nuttx/libc/unistd/lib_execv.c
@@ -0,0 +1,168 @@
+/****************************************************************************
+ * libc/unistd/lib_execv.c
+ *
+ * Copyright (C) 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 <stdlib.h>
+#include <unistd.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/binfmt/binfmt.h>
+
+#ifdef CONFIG_LIBC_EXECFUNCS
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+/* If CONFIG_LIBC_EXECFUNCS is defined in the configuration, then the
+ * following must also be defined:
+ */
+
+/* Symbol table used by exec[l|v] */
+
+#ifndef CONFIG_EXECFUNCS_SYMTAB
+# error "CONFIG_EXECFUNCS_SYMTAB must be defined"
+#endif
+
+/* Number of Symbols in the Table */
+
+#ifndef CONFIG_EXECFUNCS_NSYMBOLS
+# error "CONFIG_EXECFUNCS_NSYMBOLS must be defined"
+#endif
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+extern struct symtab_s CONFIG_EXECFUNCS_SYMTAB;
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: execv
+ *
+ * Description:
+ * The standard 'exec' family of functions will replace the current process
+ * image with a new process image. The new image will be constructed from a
+ * regular, executable file called the new process image file. There will
+ * be no return from a successful exec, because the calling process image
+ * is overlaid by the new process image.
+ *
+ * Simplified 'execl()' and 'execv()' functions are provided by NuttX for
+ * compatibility. NuttX is a tiny embedded RTOS that does not support
+ * processes and hence the concept of overlaying a tasks process image with
+ * a new process image does not make any sense. In NuttX, these functions
+ * are wrapper functions that:
+ *
+ * 1. Call the non-standard binfmt function 'exec', and then
+ * 2. exit(0).
+ *
+ * Note the inefficiency when 'exec[l|v]()' is called in the normal, two-
+ * step process: (1) first call vfork() to create a new thread, then (2)
+ * call 'exec[l|v]()' to replace the new thread with a program from the
+ * file system. Since the new thread will be terminated by the
+ * 'exec[l|v]()' call, it really served no purpose other than to suport
+ * Unix compatility.
+ *
+ * The non-standard binfmt function 'exec()' needs to have (1) a symbol
+ * table that provides the list of symbols exported by the base code, and
+ * (2) the number of symbols in that table. This information is currently
+ * provided to 'exec()' from 'exec[l|v]()' via NuttX configuration settings:
+ *
+ * CONFIG_LIBC_EXECFUNCS : Enable exec[l|v] Support
+ * CONFIG_EXECFUNCS_SYMTAB : Symbol table used by exec[l|v]
+ * CONFIG_EXECFUNCS_NSYMBOLS : Number of Symbols in the Table
+ *
+ * As a result of the above, the current implementations of 'execl()' and
+ * 'execv()' suffer from some incompatibilities that may or may not be
+ * addressed in a future version of NuttX. Other than just being an
+ * inefficient use of MCU resource, the most serious of these is that
+ * the exec'ed task will not have the same task ID as the vfork'ed
+ * function. So the parent function cannot know the ID of the exec'ed
+ * task.
+ *
+ * Input Parameters:
+ * path - The path to the program to be executed. If CONFIG_BINFMT_EXEPATH
+ * is defined in the configuration, then this may be a relative path
+ * from the current working directory. Otherwise, path must be the
+ * absolute path to the program.
+ * argv - A pointer to an array of string arguments. The end of the
+ * array is indicated with a NULL entry.
+ *
+ * Returned Value:
+ * This function does not return on success. On failure, it will return
+ * -1 (ERROR) and will set the 'errno' value appropriately.
+ *
+ ****************************************************************************/
+
+int execv(FAR const char *path, FAR char *const argv[])
+{
+ int ret;
+
+ /* Start the task */
+
+ ret = exec(path, (FAR const char **)argv,
+ &CONFIG_EXECFUNCS_SYMTAB, CONFIG_EXECFUNCS_NSYMBOLS);
+
+ if (ret < 0)
+ {
+ sdbg("exec failed: %d\n", errno);
+ return ERROR;
+ }
+
+ /* Then exit */
+
+ exit(0);
+
+ /* We should not get here, but might be needed by some compilers. Other,
+ * smarter compilers might complain that this code is unreachable. You just
+ * can't win.
+ */
+
+ return ERROR;
+}
+
+#endif /* CONFIG_LIBC_EXECFUNCS */ \ No newline at end of file