summaryrefslogtreecommitdiff
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
commit4c8b88b97559ddc6714fc17e9a281a13a65f88c0 (patch)
treebe370af4ffb6147bbbf103f66fcc69ed55bf5893
parent2e5aef172a920610e3071325b4be95b71a83948a (diff)
downloadpx4-nuttx-4c8b88b97559ddc6714fc17e9a281a13a65f88c0.tar.gz
px4-nuttx-4c8b88b97559ddc6714fc17e9a281a13a65f88c0.tar.bz2
px4-nuttx-4c8b88b97559ddc6714fc17e9a281a13a65f88c0.zip
Add execv() and execl(); Move lm3s header files for compatibility
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5492 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/ChangeLog12
-rw-r--r--nuttx/Documentation/NuttxUserGuide.html15
-rw-r--r--nuttx/arch/arm/include/lm3s/chip.h123
-rw-r--r--nuttx/arch/arm/src/lm3s/chip.h79
-rw-r--r--nuttx/arch/arm/src/lm3s/chip/lm3s_epi.h (renamed from nuttx/arch/arm/src/lm3s/lm3s_epi.h)10
-rw-r--r--nuttx/arch/arm/src/lm3s/chip/lm3s_ethernet.h (renamed from nuttx/arch/arm/src/lm3s/lm3s_ethernet.h)10
-rw-r--r--nuttx/arch/arm/src/lm3s/chip/lm3s_flash.h (renamed from nuttx/arch/arm/src/lm3s/lm3s_flash.h)10
-rw-r--r--nuttx/arch/arm/src/lm3s/chip/lm3s_gpio.h (renamed from nuttx/arch/arm/src/lm3s/lm3s_gpio.h)10
-rw-r--r--nuttx/arch/arm/src/lm3s/chip/lm3s_i2c.h (renamed from nuttx/arch/arm/src/lm3s/lm3s_i2c.h)10
-rw-r--r--nuttx/arch/arm/src/lm3s/chip/lm3s_memorymap.h (renamed from nuttx/arch/arm/src/lm3s/lm3s_memorymap.h)8
-rw-r--r--nuttx/arch/arm/src/lm3s/chip/lm3s_ssi.h (renamed from nuttx/arch/arm/src/lm3s/lm3s_ssi.h)10
-rw-r--r--nuttx/arch/arm/src/lm3s/chip/lm3s_syscontrol.h (renamed from nuttx/arch/arm/src/lm3s/lm3s_syscontrol.h)10
-rw-r--r--nuttx/arch/arm/src/lm3s/chip/lm3s_timer.h (renamed from nuttx/arch/arm/src/lm3s/lm3s_timer.h)8
-rw-r--r--nuttx/arch/arm/src/lm3s/chip/lm3s_uart.h (renamed from nuttx/arch/arm/src/lm3s/lm3s_uart.h)10
-rw-r--r--nuttx/arch/arm/src/lm3s/chip/lm_memorymap.h69
-rw-r--r--nuttx/binfmt/binfmt_exec.c21
-rw-r--r--nuttx/include/nuttx/binfmt/binfmt.h3
-rw-r--r--nuttx/include/unistd.h7
-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
-rw-r--r--nuttx/tools/cfgdefine.c1
23 files changed, 669 insertions, 123 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index e2d8a586b..ee6b088cf 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -3880,4 +3880,16 @@
OS layered architecture.
* include/unistd.h, arch/arch/src/*: Implement a simple vfork().
On initial checkin, this API is available only for ARM platforms.
+ * binfmt/binfmt_exec.c: exec() now sets the priority of the new task
+ to the same priority as the current task (instead of the arbirtrary
+ value of 50).
+ * libc/unisted/lib_execv.c and lib_execl.c: New, somewhat flawed,
+ implementations of execv() and execl().
+ * tools/cfgdefine.c: Strips quotes from CONFIG_EXECFUNCS_SYMTAB
+ value.
+ * arch/arm/include/lm3s/chip.h: Move chip definitions into
+ public include area for compatibility with other architectures.
+ * arch/arm/src/lm3s/chip: Move register definition header files
+ into a new chip/ sub-directory.
+
diff --git a/nuttx/Documentation/NuttxUserGuide.html b/nuttx/Documentation/NuttxUserGuide.html
index 5c76737e5..918b69d0f 100644
--- a/nuttx/Documentation/NuttxUserGuide.html
+++ b/nuttx/Documentation/NuttxUserGuide.html
@@ -202,6 +202,8 @@ paragraphs.
<li><a href="#taskrestart">2.1.6 task_restart</a></li>
<li><a href="#getpid">2.1.7 getpid</a></li>
<li><a href="#vfork">2.1.8 vfork</a></li>
+ <li><a href="#execv">2.1.9 execv</a></li>
+ <li><a href="#execl">2.1.10 execl</a></li>
</ul>
<H3><a name="taskcreate">2.1.1 task_create</a></H3>
@@ -648,6 +650,9 @@ pid_t vfork(void);
Compatible with the Unix interface of the same name.
</p>
+<H3><a name="execv">2.1.9 execv</a></H3>
+<H3><a name="execl">2.1.10 execl</a></H3>
+
<table width ="100%">
<tr bgcolor="#e4e4e4">
<td>
@@ -6798,6 +6803,12 @@ FAR char *getcwd(FAR char *buf, size_t size);
int unlink(FAR const char *pathname);
int rmdir(FAR const char *pathname);
+
+#ifdef CONFIG_LIBC_EXECFUNCS
+int execl(FAR const char *path, ...);
+int execv(FAR const char *path, FAR char *const argv[]);
+#endif
+
int getopt(int argc, FAR char *const argv[], FAR const char *optstring);
</pre></ul>
</a>
@@ -8198,7 +8209,9 @@ notify a task when a message is available on a queue.
<li><a href="#driveroperations">Driver operations</a></li>
<li><a href="#drvrunistdops">dup</a></li>
<li><a href="#drvrunistdops">dup2</a></li>
+ <li><a href="#execl">execl</a></li>
<li><a href="#mmapxip">eXecute In Place (XIP)</a></li>
+ <li><a href="#execv">execv</a></li>
<li><a href="#exit">exit</a></li>
<li><a href="#fatsupport">FAT File System Support</a></li>
<li><a href="#standardio">fclose</a></li>
@@ -8333,9 +8346,9 @@ notify a task when a message is available on a queue.
<li><a href="#mmapxip">ROMFS</a></li>
<li><a href="#schedgetparam">sched_getparam</a></li>
<li><a href="#schedgetprioritymax">sched_get_priority_max</a></li>
+ <li><a href="#schedgetprioritymin">sched_get_priority_min</a></li>
</td>
<td valign="top">
- <li><a href="#schedgetprioritymin">sched_get_priority_min</a></li>
<li><a href="#schedgetrrinterval">sched_get_rr_interval</a></li>
<li><a href="#schedlockcount">sched_lockcount</a></li>
<li><a href="#schedlock">sched_lock</a></li>
diff --git a/nuttx/arch/arm/include/lm3s/chip.h b/nuttx/arch/arm/include/lm3s/chip.h
new file mode 100644
index 000000000..d7e98a461
--- /dev/null
+++ b/nuttx/arch/arm/include/lm3s/chip.h
@@ -0,0 +1,123 @@
+/************************************************************************************
+ * arch/arm/include/lm3s/chip.h
+ *
+ * Copyright (C) 2009-2010, 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.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_ARM_INCLUDE_LM3S_CHIP_H
+#define __ARCH_ARM_INCLUDE_LM3S_CHIP_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Get customizations for each supported chip (only the LM3S6918 and 65 right now) */
+
+#if defined(CONFIG_ARCH_CHIP_LM3S6918)
+# define LM3S_NTIMERS 4 /* Four general purpose timers */
+# define LM3S_NETHCONTROLLERS 1 /* One Ethernet controller */
+# undef LM3S_ETHTS /* No timestamp register */
+# define LM3S_NSSI 2 /* Two SSI modules */
+# define LM3S_NUARTS 2 /* Two UART modules */
+# define LM3S_NI2C 2 /* Two I2C modules */
+# define LM3S_NADC 1 /* One ADC module */
+# define LM2S_NPWM 0 /* No PWM generator modules */
+# define LM3S_NQEI 0 /* No quadrature encoders */
+# define LM3S_NPORTS 8 /* 8 Ports (GPIOA-H) 5-38 GPIOs */
+#elif defined(CONFIG_ARCH_CHIP_LM3S6432)
+# define LM3S_NTIMERS 3 /* Three general purpose timers */
+# define LM3S_NETHCONTROLLERS 1 /* One Ethernet controller */
+# undef LM3S_ETHTS /* No timestamp register */
+# define LM3S_NSSI 1 /* One SSI module */
+# define LM3S_NUARTS 2 /* Two UART modules */
+# define LM3S_NI2C 1 /* Two I2C modules */
+# define LM3S_NADC 1 /* One ADC module */
+# define LM2S_NPWM 1 /* One PWM generator module */
+# define LM3S_NQEI 0 /* No quadrature encoders */
+# define LM3S_NPORTS 7 /* 7 Ports (GPIOA-G), 0-42 GPIOs */
+#elif defined(CONFIG_ARCH_CHIP_LM3S6965)
+# define LM3S_NTIMERS 4 /* Four general purpose timers */
+# define LM3S_NETHCONTROLLERS 1 /* One Ethernet controller */
+# undef LM3S_ETHTS /* No timestamp register */
+# define LM3S_NSSI 1 /* One SSI module */
+# define LM3S_NUARTS 3 /* Three UART modules */
+# define LM3S_NI2C 2 /* Two I2C modules */
+# define LM3S_NADC 1 /* One ADC module */
+# define LM2S_NPWM 3 /* Three PWM generator modules */
+# define LM3S_NQEI 2 /* Two quadrature encoders */
+# define LM3S_NPORTS 7 /* 7 Ports (GPIOA-G), 0-42 GPIOs */
+#elif defined(CONFIG_ARCH_CHIP_LM3S9B96)
+# define LM3S_NTIMERS 4 /* Four general purpose timers */
+# define LM3S_NETHCONTROLLERS 1 /* One Ethernet controller */
+# undef LM3S_ETHTS /* No timestamp register */
+# define LM3S_NSSI 2 /* Two SSI modules */
+# define LM3S_NUARTS 3 /* Three UART modules */
+# define LM3S_NI2C 2 /* Two I2C modules */
+# define LM3S_NADC 2 /* Two ADC module */
+# define LM3S_CAN 2 /* Two CAN module */
+# define LM3S_NPWM 4 /* Four PWM generator modules */
+# define LM3S_NQEI 2 /* Two quadrature encoders */
+# define LM3S_NPORTS 9 /* 9 Ports (GPIOA-H,J) 0-65 GPIOs */
+#elif defined(CONFIG_ARCH_CHIP_LM3S8962)
+# define LM3S_NTIMERS 4 /* Four general purpose timers */
+# define LM3S_NETHCONTROLLERS 1 /* One Ethernet controller */
+# define LM3S_NSSI 1 /* One SSI module */
+# define LM3S_NUARTS 3 /* Two UART modules */
+# define LM3S_NI2C 2 /* One I2C module */
+# define LM3S_NADC 1 /* One ADC module */
+# define LM2S_NPWM 3 /* Three PWM generator modules */
+# define LM3S_NQEI 2 /* Two quadrature encoders */
+# define LM3S_NPORTS 7 /* 7 Ports (GPIOA-G), 5-42 GPIOs */
+# define LC3S_CANCONTROLLER 1 /* One CAN controller */
+#else
+# error "Capabilities not specified for this LM3S chip"
+#endif
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#endif /* __ARCH_ARM_INCLUDE_LM3S_CHIP_H */
diff --git a/nuttx/arch/arm/src/lm3s/chip.h b/nuttx/arch/arm/src/lm3s/chip.h
index 1e22f6221..1e96b5222 100644
--- a/nuttx/arch/arm/src/lm3s/chip.h
+++ b/nuttx/arch/arm/src/lm3s/chip.h
@@ -41,83 +41,22 @@
************************************************************************************/
#include <nuttx/config.h>
+#include <arch/lm3s/chip.h>
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
-/* Get customizations for each supported chip (only the LM3S6918 and 65 right now) */
-
-#if defined(CONFIG_ARCH_CHIP_LM3S6918)
-# define LM3S_NTIMERS 4 /* Four general purpose timers */
-# define LM3S_NETHCONTROLLERS 1 /* One Ethernet controller */
-# undef LM3S_ETHTS /* No timestamp register */
-# define LM3S_NSSI 2 /* Two SSI modules */
-# define LM3S_NUARTS 2 /* Two UART modules */
-# define LM3S_NI2C 2 /* Two I2C modules */
-# define LM3S_NADC 1 /* One ADC module */
-# define LM2S_NPWM 0 /* No PWM generator modules */
-# define LM3S_NQEI 0 /* No quadrature encoders */
-# define LM3S_NPORTS 8 /* 8 Ports (GPIOA-H) 5-38 GPIOs */
-#elif defined(CONFIG_ARCH_CHIP_LM3S6432)
-# define LM3S_NTIMERS 3 /* Three general purpose timers */
-# define LM3S_NETHCONTROLLERS 1 /* One Ethernet controller */
-# undef LM3S_ETHTS /* No timestamp register */
-# define LM3S_NSSI 1 /* One SSI module */
-# define LM3S_NUARTS 2 /* Two UART modules */
-# define LM3S_NI2C 1 /* Two I2C modules */
-# define LM3S_NADC 1 /* One ADC module */
-# define LM2S_NPWM 1 /* One PWM generator module */
-# define LM3S_NQEI 0 /* No quadrature encoders */
-# define LM3S_NPORTS 7 /* 7 Ports (GPIOA-G), 0-42 GPIOs */
-#elif defined(CONFIG_ARCH_CHIP_LM3S6965)
-# define LM3S_NTIMERS 4 /* Four general purpose timers */
-# define LM3S_NETHCONTROLLERS 1 /* One Ethernet controller */
-# undef LM3S_ETHTS /* No timestamp register */
-# define LM3S_NSSI 1 /* One SSI module */
-# define LM3S_NUARTS 3 /* Three UART modules */
-# define LM3S_NI2C 2 /* Two I2C modules */
-# define LM3S_NADC 1 /* One ADC module */
-# define LM2S_NPWM 3 /* Three PWM generator modules */
-# define LM3S_NQEI 2 /* Two quadrature encoders */
-# define LM3S_NPORTS 7 /* 7 Ports (GPIOA-G), 0-42 GPIOs */
-#elif defined(CONFIG_ARCH_CHIP_LM3S9B96)
-# define LM3S_NTIMERS 4 /* Four general purpose timers */
-# define LM3S_NETHCONTROLLERS 1 /* One Ethernet controller */
-# undef LM3S_ETHTS /* No timestamp register */
-# define LM3S_NSSI 2 /* Two SSI modules */
-# define LM3S_NUARTS 3 /* Three UART modules */
-# define LM3S_NI2C 2 /* Two I2C modules */
-# define LM3S_NADC 2 /* Two ADC module */
-# define LM3S_CAN 2 /* Two CAN module */
-# define LM3S_NPWM 4 /* Four PWM generator modules */
-# define LM3S_NQEI 2 /* Two quadrature encoders */
-# define LM3S_NPORTS 9 /* 9 Ports (GPIOA-H,J) 0-65 GPIOs */
-#elif defined(CONFIG_ARCH_CHIP_LM3S8962)
-# define LM3S_NTIMERS 4 /* Four general purpose timers */
-# define LM3S_NETHCONTROLLERS 1 /* One Ethernet controller */
-# define LM3S_NSSI 1 /* One SSI module */
-# define LM3S_NUARTS 3 /* Two UART modules */
-# define LM3S_NI2C 2 /* One I2C module */
-# define LM3S_NADC 1 /* One ADC module */
-# define LM2S_NPWM 3 /* Three PWM generator modules */
-# define LM3S_NQEI 2 /* Two quadrature encoders */
-# define LM3S_NPORTS 7 /* 7 Ports (GPIOA-G), 5-42 GPIOs */
-# define LC3S_CANCONTROLLER 1 /* One CAN controller */
-#else
-# error "Capabilities not specified for this LM3S chip"
-#endif
-
/* Then get all of the register definitions */
-#include "lm3s_memorymap.h" /* Memory map */
-#include "lm3s_syscontrol.h" /* System control module */
-#include "lm3s_gpio.h" /* GPIO modules */
-#include "lm3s_uart.h" /* UART modules */
-#include "lm3s_i2c.h" /* I2C modules */
-#include "lm3s_ssi.h" /* SSI modules */
-#include "lm3s_ethernet.h" /* Ethernet MAC and PHY */
-#include "lm3s_flash.h" /* FLASH */
+#include "chip/lm_memorymap.h" /* Memory map */
+#include "chip/lm3s_syscontrol.h" /* System control module */
+#include "chip/lm3s_gpio.h" /* GPIO modules */
+#include "chip/lm3s_uart.h" /* UART modules */
+#include "chip/lm3s_i2c.h" /* I2C modules */
+#include "chip/lm3s_ssi.h" /* SSI modules */
+#include "chip/lm3s_ethernet.h" /* Ethernet MAC and PHY */
+#include "chip/lm3s_flash.h" /* FLASH */
/************************************************************************************
* Public Types
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_epi.h b/nuttx/arch/arm/src/lm3s/chip/lm3s_epi.h
index 90c9bfb7f..5b54d44ac 100644
--- a/nuttx/arch/arm/src/lm3s/lm3s_epi.h
+++ b/nuttx/arch/arm/src/lm3s/chip/lm3s_epi.h
@@ -1,7 +1,7 @@
/************************************************************************************
- * arch/arm/src/lm3s/lm3s_epi.h
+ * arch/arm/src/lm3s/chip/lm3s_epi.h
*
- * Copyright (C) 2009-2012 Max Neklyudov. All rights reserved.
+ * Copyright (C) 2009-2013 Max Neklyudov. All rights reserved.
* Author: Max Neklyudov <macscomp@gmail.com>
*
* Redistribution and use in source and binary forms, with or without
@@ -33,8 +33,8 @@
*
************************************************************************************/
-#ifndef __ARCH_ARM_SRC_LM3S_LM3S_EPI_H
-#define __ARCH_ARM_SRC_LM3S_LM3S_EPI_H
+#ifndef __ARCH_ARM_SRC_LM3S_CHIP_LM3S_EPI_H
+#define __ARCH_ARM_SRC_LM3S_CHIP_LM3S_EPI_H
/************************************************************************************
* Included Files
@@ -110,4 +110,4 @@
#define EPI_BAUD_COUNT0_MASK (0xFFFF << EPI_BAUD_COUNT0_SHIFT)
# define EPI_BAUD_COUNT0(n) ((n) << EPI_BAUD_COUNT0_SHIFT)
-#endif /* __ARCH_ARM_SRC_LM3S_LM3S_EPI_H */
+#endif /* __ARCH_ARM_SRC_LM3S_CHIP_LM3S_EPI_H */
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_ethernet.h b/nuttx/arch/arm/src/lm3s/chip/lm3s_ethernet.h
index 71833b271..940686e7d 100644
--- a/nuttx/arch/arm/src/lm3s/lm3s_ethernet.h
+++ b/nuttx/arch/arm/src/lm3s/chip/lm3s_ethernet.h
@@ -1,7 +1,7 @@
/************************************************************************************
- * arch/arm/src/lm3s/lm3s_ethernet.h
+ * arch/arm/src/lm3s/chip/lm3s_ethernet.h
*
- * Copyright (C) 2009-2010, 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2010, 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -33,8 +33,8 @@
*
************************************************************************************/
-#ifndef __ARCH_ARM_SRC_LM3S_LM3S_ETHERNET_H
-#define __ARCH_ARM_SRC_LM3S_LM3S_ETHERNET_H
+#ifndef __ARCH_ARM_SRC_LM3S_CHIP_LM3S_ETHERNET_H
+#define __ARCH_ARM_SRC_LM3S_CHIP_LM3S_ETHERNET_H
/************************************************************************************
* Included Files
@@ -200,4 +200,4 @@
* Public Function Prototypes
************************************************************************************/
-#endif /* __ARCH_ARM_SRC_LM3S_LM3S_ETHERNET_H */
+#endif /* __ARCH_ARM_SRC_LM3S_CHIP_LM3S_ETHERNET_H */
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_flash.h b/nuttx/arch/arm/src/lm3s/chip/lm3s_flash.h
index 83e388921..2bd8956b0 100644
--- a/nuttx/arch/arm/src/lm3s/lm3s_flash.h
+++ b/nuttx/arch/arm/src/lm3s/chip/lm3s_flash.h
@@ -1,7 +1,7 @@
/************************************************************************************
- * arch/arm/src/lm3s/lm3s_flash.h
+ * arch/arm/src/lm3s/chip/lm3s_flash.h
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -33,8 +33,8 @@
*
************************************************************************************/
-#ifndef __ARCH_ARM_SRC_LM3S_LM3S_FLASH_H
-#define __ARCH_ARM_SRC_LM3S_LM3S_FLASH_H
+#ifndef __ARCH_ARM_SRC_LM3S_CHIP_LM3S_FLASH_H
+#define __ARCH_ARM_SRC_LM3S_CHIP_LM3S_FLASH_H
/************************************************************************************
* Included Files
@@ -125,4 +125,4 @@
* Public Function Prototypes
************************************************************************************/
-#endif /* __ARCH_ARM_SRC_LM3S_LM3S_FLASH_H */
+#endif /* __ARCH_ARM_SRC_LM3S_CHIP_LM3S_FLASH_H */
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_gpio.h b/nuttx/arch/arm/src/lm3s/chip/lm3s_gpio.h
index 066666432..7253c1e7a 100644
--- a/nuttx/arch/arm/src/lm3s/lm3s_gpio.h
+++ b/nuttx/arch/arm/src/lm3s/chip/lm3s_gpio.h
@@ -1,7 +1,7 @@
/************************************************************************************
- * arch/arm/src/lm3s/lm3s_gpio.h
+ * arch/arm/src/lm3s/chip/lm3s_gpio.h
*
- * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2010, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -33,8 +33,8 @@
*
************************************************************************************/
-#ifndef __ARCH_ARM_SRC_LM3S_LM3S_GPIO_H
-#define __ARCH_ARM_SRC_LM3S_LM3S_GPIO_H
+#ifndef __ARCH_ARM_SRC_LM3S_CHIP_LM3S_GPIO_H
+#define __ARCH_ARM_SRC_LM3S_CHIP_LM3S_GPIO_H
/************************************************************************************
* Included Files
@@ -392,4 +392,4 @@
* Public Function Prototypes
************************************************************************************/
-#endif /* __ARCH_ARM_SRC_LM3S_LM3S_GPIO_H */
+#endif /* __ARCH_ARM_SRC_LM3S_CHIP_LM3S_GPIO_H */
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_i2c.h b/nuttx/arch/arm/src/lm3s/chip/lm3s_i2c.h
index a5f0567b9..71ebe8fcf 100644
--- a/nuttx/arch/arm/src/lm3s/lm3s_i2c.h
+++ b/nuttx/arch/arm/src/lm3s/chip/lm3s_i2c.h
@@ -1,7 +1,7 @@
/************************************************************************************
- * arch/arm/src/lm3s/lm3s_i2c.h
+ * arch/arm/src/lm3s/chip/lm3s_i2c.h
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -33,8 +33,8 @@
*
************************************************************************************/
-#ifndef __ARCH_ARM_SRC_LM3S_LM3S_I2C_H
-#define __ARCH_ARM_SRC_LM3S_LM3S_I2C_H
+#ifndef __ARCH_ARM_SRC_LM3S_CHIP_LM3S_I2C_H
+#define __ARCH_ARM_SRC_LM3S_CHIP_LM3S_I2C_H
/************************************************************************************
* Included Files
@@ -244,4 +244,4 @@
* Public Function Prototypes
****************************************************************************/
-#endif /* __ARCH_ARM_SRC_LM3S_LM3S_I2C_H */
+#endif /* __ARCH_ARM_SRC_LM3S_CHIP_LM3S_I2C_H */
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_memorymap.h b/nuttx/arch/arm/src/lm3s/chip/lm3s_memorymap.h
index be0d8b58d..31dc2b249 100644
--- a/nuttx/arch/arm/src/lm3s/lm3s_memorymap.h
+++ b/nuttx/arch/arm/src/lm3s/chip/lm3s_memorymap.h
@@ -1,5 +1,5 @@
/************************************************************************************
- * arch/arm/src/lm3s/lm3s_memorymap.h
+ * arch/arm/src/lm3s/chip/lm3s_memorymap.h
*
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@@ -33,8 +33,8 @@
*
************************************************************************************/
-#ifndef __ARCH_ARM_SRC_LM3S_LM3S_MEMORYMAP_H
-#define __ARCH_ARM_SRC_LM3S_LM3S_MEMORYMAP_H
+#ifndef __ARCH_ARM_SRC_LM3S_CHIP_LM3S_MEMORYMAP_H
+#define __ARCH_ARM_SRC_LM3S_CHIP_LM3S_MEMORYMAP_H
/************************************************************************************
* Included Files
@@ -357,4 +357,4 @@
* Public Function Prototypes
************************************************************************************/
-#endif /* __ARCH_ARM_SRC_LM3S_LM3S_MEMORYMAP_H */
+#endif /* __ARCH_ARM_SRC_LM3S_CHIP_LM3S_MEMORYMAP_H */
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_ssi.h b/nuttx/arch/arm/src/lm3s/chip/lm3s_ssi.h
index 482dab326..b56ca77cb 100644
--- a/nuttx/arch/arm/src/lm3s/lm3s_ssi.h
+++ b/nuttx/arch/arm/src/lm3s/chip/lm3s_ssi.h
@@ -1,7 +1,7 @@
/************************************************************************************
- * arch/arm/src/lm3s/lm3s_ssi.h
+ * arch/arm/src/lm3s/chip/lm3s_ssi.h
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -33,8 +33,8 @@
*
************************************************************************************/
-#ifndef __ARCH_ARM_SRC_LM3S_LM3S_SSI_H
-#define __ARCH_ARM_SRC_LM3S_LM3S_SSI_H
+#ifndef __ARCH_ARM_SRC_LM3S_CHIP_LM3S_SSI_H
+#define __ARCH_ARM_SRC_LM3S_CHIP_LM3S_SSI_H
/************************************************************************************
* Included Files
@@ -232,4 +232,4 @@
************************************************************************************/
#endif /* LM3S_NSSI > 0 */
-#endif /* __ARCH_ARM_SRC_LM3S_LM3S_SSI_H */
+#endif /* __ARCH_ARM_SRC_LM3S_CHIP_LM3S_SSI_H */
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_syscontrol.h b/nuttx/arch/arm/src/lm3s/chip/lm3s_syscontrol.h
index c59b921c4..d66cfeb47 100644
--- a/nuttx/arch/arm/src/lm3s/lm3s_syscontrol.h
+++ b/nuttx/arch/arm/src/lm3s/chip/lm3s_syscontrol.h
@@ -1,7 +1,7 @@
/************************************************************************************
- * arch/arm/src/lm3s/lm3s_syscontrol.h
+ * arch/arm/src/lm3s/chip/lm3s_syscontrol.h
*
- * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2010, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -33,8 +33,8 @@
*
************************************************************************************/
-#ifndef __ARCH_ARM_SRC_LM3S_LM3S_SYSCONTROL_H
-#define __ARCH_ARM_SRC_LM3S_LM3S_SYSCONTROL_H
+#ifndef __ARCH_ARM_SRC_LM3S_CHIP_LM3S_SYSCONTROL_H
+#define __ARCH_ARM_SRC_LM3S_CHIP_LM3S_SYSCONTROL_H
/************************************************************************************
* Included Files
@@ -492,4 +492,4 @@
* Public Functions
************************************************************************************/
-#endif /* __ARCH_ARM_SRC_LM3S_LM3S_SYSCONTROL_H */
+#endif /* __ARCH_ARM_SRC_LM3S_CHIP_LM3S_SYSCONTROL_H */
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_timer.h b/nuttx/arch/arm/src/lm3s/chip/lm3s_timer.h
index 7c4166293..649737f13 100644
--- a/nuttx/arch/arm/src/lm3s/lm3s_timer.h
+++ b/nuttx/arch/arm/src/lm3s/chip/lm3s_timer.h
@@ -1,5 +1,5 @@
/************************************************************************************
- * arch/arm/src/lm3s/lm3s_timer.h
+ * arch/arm/src/lm3s/chip/lm3s_timer.h
*
* Copyright (C) 2012 Max Nekludov. All rights reserved.
* Author: Max Nekludov <macscomp@gmail.com>
@@ -33,8 +33,8 @@
*
************************************************************************************/
-#ifndef __ARCH_ARM_SRC_LM3S_LM3S_TIMER_H
-#define __ARCH_ARM_SRC_LM3S_LM3S_TIMER_H
+#ifndef __ARCH_ARM_SRC_LM3S_CHIP_LM3S_TIMER_H
+#define __ARCH_ARM_SRC_LM3S_CHIP_LM3S_TIMER_H
/************************************************************************************
* Included Files
@@ -122,4 +122,4 @@
#define TIMER_GPTMICR_TATOCINT_SHIFT 0 /* Bits 0: GPTM Timer A Time-Out Raw Interrupt Clear*/
#define TIMER_GPTMICR_TATOCINT_MASK (0x01 << TIMER_GPTMICR_TATOCINT_SHIFT)
-#endif /* __ARCH_ARM_SRC_LM3S_LM3S_TIMER_H */
+#endif /* __ARCH_ARM_SRC_LM3S_CHIP_LM3S_TIMER_H */
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_uart.h b/nuttx/arch/arm/src/lm3s/chip/lm3s_uart.h
index 91bfb2266..0fef5ccf7 100644
--- a/nuttx/arch/arm/src/lm3s/lm3s_uart.h
+++ b/nuttx/arch/arm/src/lm3s/chip/lm3s_uart.h
@@ -1,7 +1,7 @@
/************************************************************************************
- * arch/arm/src/lm3s/lm3s_uart.h
+ * arch/arm/src/lm3s/chip/lm3s_uart.h
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -33,8 +33,8 @@
*
************************************************************************************/
-#ifndef __ARCH_ARM_SRC_LM3S_LM3S_UART_H
-#define __ARCH_ARM_SRC_LM3S_LM3S_UART_H
+#ifndef __ARCH_ARM_SRC_LM3S_CHIP_LM3S_UART_H
+#define __ARCH_ARM_SRC_LM3S_CHIP_LM3S_UART_H
/************************************************************************************
* Included Files
@@ -344,4 +344,4 @@
* Public Functions
************************************************************************************/
-#endif /* __ARCH_ARM_SRC_LM3S_LM3S_UART_H */
+#endif /* __ARCH_ARM_SRC_LM3S_CHIP_LM3S_UART_H */
diff --git a/nuttx/arch/arm/src/lm3s/chip/lm_memorymap.h b/nuttx/arch/arm/src/lm3s/chip/lm_memorymap.h
new file mode 100644
index 000000000..c52857847
--- /dev/null
+++ b/nuttx/arch/arm/src/lm3s/chip/lm_memorymap.h
@@ -0,0 +1,69 @@
+/************************************************************************************
+ * arch/arm/src/lm3s/chip/lm_memorymap.h
+ *
+ * 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.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_LM3S_CHIP_LM_MEMORYMAP_H
+#define __ARCH_ARM_SRC_LM3S_CHIP_LM_MEMORYMAP_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/* Include the memory map file for the specific Stellaris chip */
+
+#ifdef CONFIG_ARCH_CHIP_LM3S
+# include "chip/lm3s_memorymap.h"
+#else
+# error "Unsupported Stellaris memory map"
+#endif
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Function Prototypes
+ ************************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_LM3S_CHIP_LM_MEMORYMAP_H */
diff --git a/nuttx/binfmt/binfmt_exec.c b/nuttx/binfmt/binfmt_exec.c
index 60e8d8efd..d5e274710 100644
--- a/nuttx/binfmt/binfmt_exec.c
+++ b/nuttx/binfmt/binfmt_exec.c
@@ -1,7 +1,7 @@
/****************************************************************************
* binfmt/binfmt_exec.c
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -75,7 +75,8 @@
*
* Description:
* This is a convenience function that wraps load_ and exec_module into
- * one call.
+ * one call. The priority of the executed program is set to be the
+ * same as the priority of the calling thread.
*
* Input Parameter:
* filename - Fulll path to the binary to be loaded
@@ -94,8 +95,20 @@ int exec(FAR const char *filename, FAR const char **argv,
FAR const struct symtab_s *exports, int nexports)
{
struct binary_s bin;
+ struct sched_param param;
int ret;
+ /* Get the priority of this thread */
+
+ ret = sched_getparam(0, &param);
+ if (ret < 0)
+ {
+ bdbg("ERROR: sched_getparam failed: %d\n", errno);
+ return ERROR;
+ }
+
+ /* Load the module into memory */
+
memset(&bin, 0, sizeof(struct binary_s));
bin.filename = filename;
bin.exports = exports;
@@ -108,7 +121,9 @@ int exec(FAR const char *filename, FAR const char **argv,
return ERROR;
}
- ret = exec_module(&bin, 50);
+ /* Then start the module at the priority of this thread */
+
+ ret = exec_module(&bin, param.sched_priority);
if (ret < 0)
{
bdbg("ERROR: Failed to execute program '%s'\n", filename);
diff --git a/nuttx/include/nuttx/binfmt/binfmt.h b/nuttx/include/nuttx/binfmt/binfmt.h
index 6df5190d2..480e82c09 100644
--- a/nuttx/include/nuttx/binfmt/binfmt.h
+++ b/nuttx/include/nuttx/binfmt/binfmt.h
@@ -228,7 +228,8 @@ int exec_module(FAR const struct binary_s *bin, int priority);
*
* Description:
* This is a convenience function that wraps load_ and exec_module into
- * one call.
+ * one call. The priority of the executed program is set to be the
+ * same as the priority of the calling thread.
*
* Input Parameter:
* filename - Fulll path to the binary to be loaded
diff --git a/nuttx/include/unistd.h b/nuttx/include/unistd.h
index ddb6880f4..d2ace79fa 100644
--- a/nuttx/include/unistd.h
+++ b/nuttx/include/unistd.h
@@ -160,6 +160,13 @@ EXTERN FAR char *getcwd(FAR char *buf, size_t size);
EXTERN int unlink(FAR const char *pathname);
EXTERN int rmdir(FAR const char *pathname);
+/* Execution of programs from files */
+
+#ifdef CONFIG_LIBC_EXECFUNCS
+EXTERN int execl(FAR const char *path, ...);
+EXTERN int execv(FAR const char *path, FAR char *const argv[]);
+#endif
+
/* Other */
EXTERN int getopt(int argc, FAR char *const argv[], FAR const char *optstring);
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
diff --git a/nuttx/tools/cfgdefine.c b/nuttx/tools/cfgdefine.c
index ee1dd4003..f026a186f 100644
--- a/nuttx/tools/cfgdefine.c
+++ b/nuttx/tools/cfgdefine.c
@@ -64,6 +64,7 @@ static const char *dequote_list[] =
/* NuttX */
"CONFIG_USER_ENTRYPOINT", /* Name of entry point function */
+ "CONFIG_EXECFUNCS_SYMTAB", /* Symbol table used by exec[l|v] */
/* NxWidgets/NxWM */