From 6f241ed0443cc265d7a079f4bbf8d2d67be939ff Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 10 Jan 2013 20:00:08 +0000 Subject: [PATCH] Add interfaces to dynamically change symbol tables used by posix_spawn, execv, and execl. This is needed for testing. git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5506 42af7a65-404d-4744-a932-0658087f49c3 --- apps/examples/Make.defs | 4 + apps/examples/Makefile | 4 +- apps/examples/README.txt | 84 ++++++++++++++++- nuttx/include/unistd.h | 6 ++ nuttx/libc/spawn/lib_ps.c | 53 +++++++++-- nuttx/libc/spawn/spawn.h | 2 +- nuttx/libc/unistd/Make.defs | 2 +- nuttx/libc/unistd/lib_execsymtab.c | 147 +++++++++++++++++++++++++++++ nuttx/libc/unistd/lib_execv.c | 31 ++---- 9 files changed, 292 insertions(+), 41 deletions(-) create mode 100644 nuttx/libc/unistd/lib_execsymtab.c diff --git a/apps/examples/Make.defs b/apps/examples/Make.defs index de2b8939fe..68d4d43406 100644 --- a/apps/examples/Make.defs +++ b/apps/examples/Make.defs @@ -182,6 +182,10 @@ ifeq ($(CONFIG_EXAMPLES_PWM),y) CONFIGURED_APPS += examples/pwm endif +ifeq ($(CONFIG_EXAMPLES_POSIXSPAWN),y) +CONFIGURED_APPS += examples/posix_spawn +endif + ifeq ($(CONFIG_EXAMPLES_QENCODER),y) CONFIGURED_APPS += examples/qencoder endif diff --git a/apps/examples/Makefile b/apps/examples/Makefile index 99312af7ab..a11dbf2405 100644 --- a/apps/examples/Makefile +++ b/apps/examples/Makefile @@ -40,8 +40,8 @@ SUBDIRS = adc buttons can cdcacm composite cxxtest dhcpd discover elf ftpc SUBDIRS += ftpd hello helloxx hidkbd igmp json keypadtest lcdrw mm modbus mount SUBDIRS += nettest nsh null nx nxconsole nxffs nxflat nxhello nximage -SUBDIRS += nxlines nxtext ostest pashello pipe poll pwm qencoder relays -SUBDIRS += rgmp romfs serloop telnetd thttpd tiff touchscreen udp uip +SUBDIRS += nxlines nxtext ostest pashello pipe poll pwm posix_spawn qencoder +SUBDIRS += relays rgmp romfs serloop telnetd thttpd tiff touchscreen udp uip SUBDIRS += usbserial sendmail usbstorage usbterm watchdog wget wgetjson # Sub-directories that might need context setup. Directories may need diff --git a/apps/examples/README.txt b/apps/examples/README.txt index 7bfba721a6..5c6332ee33 100644 --- a/apps/examples/README.txt +++ b/apps/examples/README.txt @@ -329,10 +329,10 @@ examples/elf each program in the ROMFS file system is executed. Requires CONFIG_ELF. Other configuration options: - CONFIG_EXAMPLES_ELF_DEVMINOR - The minor device number of the ROMFS block. - For example, the N in /dev/ramN. Used for registering the RAM block driver - that will hold the ROMFS file system containing the ELF executables to be - tested. Default: 0 + CONFIG_EXAMPLES_ELF_DEVMINOR - The minor device number of the ROMFS block + driver. For example, the N in /dev/ramN. Used for registering the RAM + block driver that will hold the ROMFS file system containing the ELF + executables to be tested. Default: 0 CONFIG_EXAMPLES_ELF_DEVPATH - The path to the ROMFS block driver device. This must match EXAMPLES_ELF_DEVMINOR. Used for registering the RAM block driver @@ -348,7 +348,7 @@ examples/elf Similarly for C++ flags which must be provided in CXXELFFLAGS. - 2. Your top-level nuttx/Make.defs file must alos include an approproate definition, + 2. Your top-level nuttx/Make.defs file must also include an approproate definition, LDELFFLAGS, to generate a relocatable ELF object. With GNU LD, this should include '-r' and '-e main' (or _main on some platforms). @@ -1202,6 +1202,80 @@ examples/poll CONFIGURED_APPS += uiplib +examples/posix_spawn +^^^^^^^^^^^^^^^^^^^^ + + This is a simple test of the posix_spawn() API. The example derives from + examples/elf. As a result, these tests are built using the relocatable + ELF format installed in a ROMFS file system. At run time, the test program + in the ROMFS file system is spawned using posix_spawn(). + + Requires: + + CONFIG_BINFMT_DISABLE=n - Don't disable the binary loader + CONFIG_ELF=y - Enable ELF binary loader + CONFIG_LIBC_EXECFUNCS=y - Enable support for posix_spawn + CONFIG_EXECFUNCS_SYMTAB="exports" - The name of the symbol table + created by the test. + CONFIG_EXECFUNCS_NSYMBOLS=10 - Value does not matter, it will be + corrected at runtime. + CONFIG_POSIX_SPAWN_STACKSIZE=768 - This default setting. + + Test-specific configuration options: + + CONFIG_EXAMPLES_POSIXSPAWN_DEVMINOR - The minor device number of the ROMFS + block. driver. For example, the N in /dev/ramN. Used for registering the + RAM block driver that will hold the ROMFS file system containing the ELF + executables to be tested. Default: 0 + + CONFIG_EXAMPLES_POSIXSPAWN_DEVPATH - The path to the ROMFS block driver + device. This must match EXAMPLES_POSIXSPAWN_DEVMINOR. Used for + registering the RAM block driver that will hold the ROMFS file system + containing the ELF executables to be tested. Default: "/dev/ram0" + + NOTES: + + 1. CFLAGS should be provided in CELFFLAGS. RAM and FLASH memory regions + may require long allcs. For ARM, this might be: + + CELFFLAGS = $(CFLAGS) -mlong-calls + + Similarly for C++ flags which must be provided in CXXELFFLAGS. + + 2. Your top-level nuttx/Make.defs file must also include an approproate + definition, LDELFFLAGS, to generate a relocatable ELF object. With GNU + LD, this should include '-r' and '-e main' (or _main on some platforms). + + LDELFFLAGS = -r -e main + + If you use GCC to link, you make also need to include '-nostdlib' or + '-nostartfiles' and '-nodefaultlibs'. + + 3. This example also requires genromfs. genromfs can be build as part of the + nuttx toolchain. Or can built from the genromfs sources that can be found + at misc/tools/genromfs-0.5.2.tar.gz. In any event, the PATH variable must + include the path to the genromfs executable. + + 4. ELF size: The ELF files in this example are, be default, quite large + because they include a lot of "build garbage". You can greatly reduce the + size of the ELF binaries are using the 'objcopy --strip-unneeded' command to + remove un-necessary information from the ELF files. + + 5. Simulator. You cannot use this example with the the NuttX simulator on + Cygwin. That is because the Cygwin GCC does not generate ELF file but + rather some Windows-native binary format. + + If you really want to do this, you can create a NuttX x86 buildroot toolchain + and use that be build the ELF executables for the ROMFS file system. + + 6. Linker scripts. You might also want to use a linker scripts to combine + sections better. An example linker script is at nuttx/binfmt/libelf/gnu-elf.ld. + That example might have to be tuned for your particular linker output to + position additional sections correctly. The GNU LD LDELFFLAGS then might + be: + + LDELFFLAGS = -r -e main -T$(TOPDIR)/binfmt/libelf/gnu-elf.ld + examples/pwm ^^^^^^^^^^^^ diff --git a/nuttx/include/unistd.h b/nuttx/include/unistd.h index d2ace79fa3..c5289624bd 100644 --- a/nuttx/include/unistd.h +++ b/nuttx/include/unistd.h @@ -165,6 +165,12 @@ EXTERN int rmdir(FAR const char *pathname); #ifdef CONFIG_LIBC_EXECFUNCS EXTERN int execl(FAR const char *path, ...); EXTERN int execv(FAR const char *path, FAR char *const argv[]); + +/* Non-standard functions to manage symbol tables */ + +struct symtab_s; /* See include/nuttx/binfmt/symtab.h */ +EXTERN void exec_getsymtab(FAR struct symtab_s **symtab, FAR int *nsymbols); +EXTERN void exec_setsymtab(FAR const struct symtab_s *symtab, int nsymbols); #endif /* Other */ diff --git a/nuttx/libc/spawn/lib_ps.c b/nuttx/libc/spawn/lib_ps.c index b0f6e1b07f..7509d67377 100644 --- a/nuttx/libc/spawn/lib_ps.c +++ b/nuttx/libc/spawn/lib_ps.c @@ -157,11 +157,17 @@ static int ps_exec(FAR pid_t *pidp, FAR const char *path, FAR char *const argv[]) { struct sched_param param; + FAR struct symtab_s *symtab; + int nsymbols; int pid; int ret = OK; DEBUGASSERT(path); + /* Get the current symbol table selection */ + + exec_getsymtab(&symtab, &nsymbols); + /* Disable pre-emption so that we can modify the task parameters after * we start the new task; the new task will not actually begin execution * until we re-enable pre-emption. @@ -171,13 +177,11 @@ static int ps_exec(FAR pid_t *pidp, FAR const char *path, /* Start the task */ - pid = exec(path, (FAR const char **)argv, &CONFIG_EXECFUNCS_SYMTAB, - CONFIG_EXECFUNCS_NSYMBOLS); - + pid = exec(path, (FAR const char **)argv, symtab, nsymbols); if (pid < 0) { ret = errno; - sdbg("exec failed: %d\n", ret); + sdbg("ERROR: exec failed: %d\n", ret); goto errout; } @@ -211,6 +215,9 @@ static int ps_exec(FAR pid_t *pidp, FAR const char *path, if ((attr->flags & POSIX_SPAWN_SETSCHEDULER) == 0) { + svdbg("Setting priority=%d for pid=%d\n", + param.sched_priority, pid); + (void)sched_setparam(pid, ¶m); } } @@ -231,6 +238,9 @@ static int ps_exec(FAR pid_t *pidp, FAR const char *path, if ((attr->flags & POSIX_SPAWN_SETSCHEDULER) != 0) { + svdbg("Setting policy=%d priority=%d for pid=%d\n", + attr->policy, param.sched_priority, pid); + (void)sched_setscheduler(pid, attr->policy, ¶m); } } @@ -262,18 +272,27 @@ static inline int spawn_close(FAR struct spawn_close_file_action_s *action) { /* The return value from close() is ignored */ + svdbg("Closing fd=%d\n", action->fd); + (void)close(action->fd); return OK; } static inline int spawn_dup2(FAR struct spawn_dup2_file_action_s *action) { + int ret; + /* Perform the dup */ - int ret = dup2(action->fd1, action->fd2); + svdbg("Dup'ing %d->%d\n", action->fd1, action->fd2); + + ret = dup2(action->fd1, action->fd2); if (ret < 0) { - return errno; + int errcode = errno; + + sdbg("ERROR: dup2 failed: %d\n", errcode); + return errcode; } return OK; @@ -286,10 +305,14 @@ static inline int spawn_open(FAR struct spawn_open_file_action_s *action) /* Open the file */ + svdbg("Open'ing path=%s oflags=%04x mode=%04x\n", + action->path, action->oflags, action->mode); + fd = open(action->path, action->oflags, action->mode); if (fd < 0) { ret = errno; + sdbg("ERROR: open failed: %d\n", ret); } /* Does the return file descriptor happen to match the required file @@ -300,12 +323,16 @@ static inline int spawn_open(FAR struct spawn_open_file_action_s *action) { /* No.. dup2 to get the correct file number */ + svdbg("Dup'ing %d->%d\n", fd, action->fd); + ret = dup2(fd, action->fd); if (ret < 0) { ret = errno; + sdbg("ERROR: dup2 failed: %d\n", ret); } + svdbg("Closing fd=%d\n", fd); close(fd); } @@ -379,6 +406,7 @@ static int spawn_proxy(int argc, char *argv[]) case SPAWN_FILE_ACTION_NONE: default: + sdbg("ERROR: Unknown action: %d\n", entry->action); ret = EINVAL; break; } @@ -517,6 +545,9 @@ int posix_spawn(FAR pid_t *pid, FAR const char *path, DEBUGASSERT(path); + svdbg("pid=%p path=%s file_actions=%p attr=%p argv=%p\n", + pid, path, file_actions, attr, argv); + /* If there are no file actions to be performed and there is no change to * the signal mask, then start the new child task directly from the parent task. */ @@ -559,8 +590,11 @@ int posix_spawn(FAR pid_t *pid, FAR const char *path, ret = sched_getparam(0, ¶m); if (ret < 0) { + int errcode = errno; + + sdbg("ERROR: sched_getparam failed: %d\n", errcode); ps_semgive(&g_ps_parmsem); - return errno; + return errcode; } /* Start the intermediary/proxy task at the same priority as the parent task. */ @@ -570,8 +604,11 @@ int posix_spawn(FAR pid_t *pid, FAR const char *path, (const char **)NULL); if (proxy < 0) { + int errcode = errno; + + sdbg("ERROR: Failed to start spawn_proxy: %d\n", errcode); ps_semgive(&g_ps_parmsem); - return errno; + return errcode; } /* Wait for the proxy to complete its job */ diff --git a/nuttx/libc/spawn/spawn.h b/nuttx/libc/spawn/spawn.h index 5d0159ff28..3f4e195cc7 100644 --- a/nuttx/libc/spawn/spawn.h +++ b/nuttx/libc/spawn/spawn.h @@ -1,7 +1,7 @@ /**************************************************************************** * libc/spawn/spawn.h * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without diff --git a/nuttx/libc/unistd/Make.defs b/nuttx/libc/unistd/Make.defs index 3811673bf5..ee3ac0fc93 100644 --- a/nuttx/libc/unistd/Make.defs +++ b/nuttx/libc/unistd/Make.defs @@ -43,7 +43,7 @@ CSRCS += lib_chdir.c lib_getcwd.c endif ifeq ($(CONFIG_LIBC_EXECFUNCS),y) -CSRCS += lib_execl.c lib_execv.c +CSRCS += lib_execl.c lib_execv.c lib_execsymtab.c endif endif diff --git a/nuttx/libc/unistd/lib_execsymtab.c b/nuttx/libc/unistd/lib_execsymtab.c new file mode 100644 index 0000000000..e95107d15e --- /dev/null +++ b/nuttx/libc/unistd/lib_execsymtab.c @@ -0,0 +1,147 @@ +/**************************************************************************** + * libc/unistd/lib_execsymtab.c + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include +#include + +#ifdef CONFIG_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 + +/**************************************************************************** + * Public Variables + ****************************************************************************/ + +extern struct symtab_s CONFIG_EXECFUNCS_SYMTAB; + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static FAR struct symtab_s *g_exec_symtab = &CONFIG_EXECFUNCS_SYMTAB; +static int g_exec_nsymbols = CONFIG_EXECFUNCS_NSYMBOLS; + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: exec_getsymtab + * + * Description: + * Get the current symbol table selection as an atomic operation. + * + * Input Parameters: + * symtab - The location to store the symbol table. + * nsymbols - The location to store the number of symbols in the symbol table. + * + * Returned Value: + * None + * + ****************************************************************************/ + +void exec_getsymtab(FAR struct symtab_s **symtab, FAR int *nsymbols) +{ + irqstate_t flags; + + DEBUGASSERT(symtab && nsymbols); + + /* Disable interrupts very briefly so that both the symbol table and its + * size are returned as a single atomic operation. + */ + + flags = irqsave(); + *symtab = g_exec_symtab; + *nsymbols = g_exec_nsymbols; + irqrestore(flags); +} + +/**************************************************************************** + * Name: exec_setsymtab + * + * Description: + * Select a new symbol table selection as an atomic operation. + * + * Input Parameters: + * symtab - The new symbol table. + * nsymbols - The number of symbols in the symbol table. + * + * Returned Value: + * None + * + ****************************************************************************/ + +void exec_setsymtab(FAR const struct symtab_s *symtab, int nsymbols) +{ + irqstate_t flags; + + DEBUGASSERT(symtab); + + /* Disable interrupts very briefly so that both the symbol table and its + * size are set as a single atomic operation. + */ + + flags = irqsave(); + g_exec_symtab = symtab; + g_exec_nsymbols = nsymbols; + irqrestore(flags); +} + +#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 index 6d09bf4815..e35138be5e 100644 --- a/nuttx/libc/unistd/lib_execv.c +++ b/nuttx/libc/unistd/lib_execv.c @@ -51,27 +51,6 @@ /**************************************************************************** * 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 - -/**************************************************************************** - * Public Variables - ****************************************************************************/ - -extern struct symtab_s CONFIG_EXECFUNCS_SYMTAB; /**************************************************************************** * Private Variables @@ -140,13 +119,17 @@ extern struct symtab_s CONFIG_EXECFUNCS_SYMTAB; int execv(FAR const char *path, FAR char *const argv[]) { + FAR struct symtab_s *symtab; + int nsymbols; int ret; - /* Start the task */ + /* Get the current symbol table selection */ - ret = exec(path, (FAR const char **)argv, - &CONFIG_EXECFUNCS_SYMTAB, CONFIG_EXECFUNCS_NSYMBOLS); + exec_getsymtab(&symtab, &nsymbols); + + /* Start the task */ + ret = exec(path, (FAR const char **)argv, symtab, nsymbols); if (ret < 0) { sdbg("exec failed: %d\n", errno);