Add basic hooks to support a PATH variable (more is needed)

git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5440 42af7a65-404d-4744-a932-0658087f49c3
This commit is contained in:
patacongo 2012-12-16 21:15:27 +00:00
parent 8fc05d82fc
commit 14a896b205
11 changed files with 485 additions and 31 deletions

View File

@ -3782,4 +3782,13 @@
* arch/z80/src/z180/z180_mmu.*: Add MMU support for z180 tasks.
* configs/p112: Add very basic board support and an examples/ostest
configuration for the venerable P112 board.
* sched/os_bringup.c: If CONFIG_PATH_INITIAL is defined, then the initial
environment of the task started by os_bringup() will have the PATH
environment variable defined to be that string.
* binfmt/binfmt_exepath.c: If CONFIG_BINFMT_EXEPATH is defined, then this
file will be built. In contains logic to search for regular files at
the absolutes paths found in the current PATH environment variable
setting. This is untested and not yet hooked into the binfmt exec()
logic on initial check-in

View File

@ -35,12 +35,12 @@ nuttx/
(4) ARM/STM32 (arch/arm/src/stm32/)
(3) AVR (arch/avr)
(0) Intel x86 (arch/x86)
(4) 8051 / MCS51 (arch/8051/)
(5) 8051 / MCS51 (arch/8051/)
(3) MIPS/PIC32 (arch/mips)
(1) Hitachi/Renesas SH-1 (arch/sh/src/sh1)
(4) Renesas M16C/26 (arch/sh/src/m16c)
(10) z80/z8/ez80 (arch/z80/)
(8) z16 (arch/z16/)
(9) z16 (arch/z16/)
(1) mc68hc1x (arch/hc)
apps/
@ -1505,6 +1505,16 @@ o 8051 / MCS51 (arch/8051/)
Status: Open
Priority: Low -- only because there as so many other issues with 8051
Title: 8051 BUILD BROKEN
Description: The last time I tried to build the pjrc-8051 configurtion using
the SDCC 3.2.1 toolchain (for Windows). I got compilation
errors in sched/os_bringup.c. It complained about type
mis-matches. What I gather from Googling, this is a problem
with the --stack-auto option. At any rate, this problem will
need to be fixed if you want to resurrect the 8051 NuttX port.
Status: Open
Priority: Low -- I don't think anyone uses the 8051 port.
o MIPS/PIC32(arch/mips)
^^^^^^^^^^^^^^^^^^^^^
@ -1837,6 +1847,14 @@ o z16 (arch/z16)
drivers/mmcsd/Make.defs. There is no SDIO support for the Z16 anyway
Priority: Low
Title: NATIVE BUILD PROBLEMS
Description: When last tested (ca.12/12), there were some missing .obj files in
arch/z16/src. A little additional TLC will be needed to get a
reliable Windows native build. As of this writing, the Cygwin
based build has not been re-verified.
Status: Open
Priority: Low -- I don't think anyone uses the Z16 port.
o mc68hc1x (arch/hc)
^^^^^^^^^^^^^^^^^^

View File

@ -12,6 +12,22 @@ config BINFMT_DISABLE
if !BINFMT_DISABLE
config BINFMT_EXEPATH
bool "Support PATH variable"
default n
depends on !DISABLE_ENVIRON
---help---
Use the contents of the PATH environment variable to locate executable
files. Default: n
config PATH_INITIAL
string "Initial PATH Value"
default ""
depends on BINFMT_EXEPATH
---help---
The initial value of the PATH variable. This is the colon-separated
list of absolute paths. E.g., "/bin:/usr/bin:/sbin"
config NXFLAT
bool "Enable the NXFLAT Binary Format"
default n

View File

@ -44,14 +44,18 @@ CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" "$(TOPDIR)$(DELIM)sched"}
# Basic BINFMT source files
BINFMT_ASRCS =
BINFMT_CSRCS = binfmt_globals.c binfmt_register.c binfmt_unregister.c \
binfmt_loadmodule.c binfmt_unloadmodule.c binfmt_execmodule.c \
binfmt_exec.c binfmt_dumpmodule.c
BINFMT_CSRCS = binfmt_globals.c binfmt_register.c binfmt_unregister.c
BINFMT_CSRCS += binfmt_loadmodule.c binfmt_unloadmodule.c binfmt_execmodule.c
BINFMT_CSRCS += binfmt_exec.c binfmt_dumpmodule.c
ifeq ($(CONFIG_BINFMT_EXEPATH),y)
BINFMT_CSRCS += binfmt_exepath.c
endif
# Symbol table source files
BINFMT_CSRCS += symtab_findbyname.c symtab_findbyvalue.c \
symtab_findorderedbyname.c symtab_findorderedbyvalue.c
BINFMT_CSRCS += symtab_findbyname.c symtab_findbyvalue.c
BINFMT_CSRCS += symtab_findorderedbyname.c symtab_findorderedbyvalue.c
# Add configured binary modules

View File

@ -0,0 +1,285 @@
/****************************************************************************
* binfmt/binfmt_exepath.c
*
* Copyright (C) 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 <sys/types.h>
#include <sys/stat.h>
#include <stdlib.h>
#include <string.h>
#include <assert.h>
#include <nuttx/kmalloc.h>
#include <nuttx/binfmt/binfmt.h>
#if !defined(CONFIG_BINFMT_DISABLE) && defined(CONFIG_BINFMT_EXEPATH)
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Private Types
****************************************************************************/
struct exepath_s
{
FAR char *next; /* Pointer to the next (unterminated) value in the PATH variable */
char path[1];
};
#define SIZEOF_EXEPATH_S(n) (sizeof(struct exepath_s) + (n) - 1)
/****************************************************************************
* Private Data
****************************************************************************/
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: exepath_init
*
* Description:
* Initialize for the traversal of each value in the PATH variable. The
* usage is sequence is as follows:
*
* 1) Call exepath_init() to initialze for the traversal. exepath_init()
* will return an opaque handle that can then be provided to
* exepath_next() and exepath_release().
* 2) Call exepath_next() repeatedly to examine every file that lies
* in the directories of the PATH variable
* 3) Call exepath_release() to free resources set aside by exepath_init().
*
* Input Parameters:
* None
*
* Returned Value:
* On success, exepath_init() return a non-NULL, opaque handle that may
* subsequently be used in calls to exepath_next() and exepath_release().
* On error, a NULL handle value will be returned. The most likely cause
* of an error would be that the there is no value associated with the
* PATH variable.
*
****************************************************************************/
EXEPATH_HANDLE exepath_init(void)
{
FAR struct exepath_s *exepath;
FAR char *path;
/* Get the value of the PATH variable */
path = getenv("PATH");
if (!path)
{
/* getenv() will return a NULL value if the PATH variable does not
* exist in the environment.
*/
return (EXEPATH_HANDLE)NULL;
}
/* Allocate a container for the PATH variable contents */
exepath = (FAR struct exepath_s *)kmalloc(SIZEOF_EXEPATH_S(strlen(path) + 1));
if (!exepath)
{
/* Ooops.. we are out of memory */
return (EXEPATH_HANDLE)NULL;
}
/* Populate the container */
strcpy(exepath->path, path);
exepath->next = exepath->path;
/* And return the containing cast to an opaque handle */
return (EXEPATH_HANDLE)exepath;
}
/****************************************************************************
* Name: exepath_next
*
* Description:
* Traverse all possible values in the PATH variable in attempt to find
* the full path to an executable file when only a relative path is
* provided.
*
* Input Parameters:
* handle - The handle value returned by exepath_init
* relpath - The relative path to the file to be found.
*
* Returned Value:
* On success, a non-NULL pointer to a null-terminated string is provided.
* This is the full path to a file that exists in the file system. This
* function will verify that the file exists (but will not verify that it
* is marked executable).
*
* NOTE: The string pointer return in the success case points to allocated
* memory. This memory must be freed by the called by calling kfree().
*
* NULL is returned if no path is found to any file with the provided
* 'relpath' from any absolute path in the file variable. In this case,
* there is no point in calling exepath_next() further; exepath_release()
* must be called to release resources set aside by expath_init().
*
****************************************************************************/
FAR char *exepath_next(EXEPATH_HANDLE handle, FAR const char *relpath)
{
FAR struct exepath_s *exepath = (FAR struct exepath_s *)handle;
struct stat buf;
FAR char *endptr;
FAR char *path;
FAR char *fullpath;
int pathlen;
int ret;
/* Verify that a value handle and relative path were provided */
DEBUGASSERT(exepath && relpath);
DEBUGASSERT(relpath[0] != '\0' && relpath[0] != '/');
/* Loop until (1) we find a file with this relative path from one of the
* absolute paths in the PATH variable, or (2) all of the absolute paths
* in the PATH variable have been considered.
*/
for (;;)
{
/* Make sure that exepath->next points to the beginning of a string */
path = exepath->next;
if (*path == '\0')
{
/* If it points to a NULL it means that either (1) the PATH varialbe
* is empty, or (2) we have already examined all of the paths in the
* path variable.
*/
return (FAR char *)NULL;
}
/* Okay... 'path' points to the beginning of the string. The string may
* be termined either with (1) ':' which separates the path from the
* next path in the list, or (2) NUL which marks the end of the list.
*/
endptr = strchr(path, ':');
if (!endptr)
{
/* If strchr returns NUL it means that ':' does not appear in the
* string. Therefore, this must be the final path in the PATH
* variable content.
*/
endptr = &path[strlen(path)];
exepath->next = endptr;
DEBUGASSERT(*endptr == '\0');
}
else
{
DEBUGASSERT(*endptr == ':');
exepath->next = endptr + 1;
*endptr = '\0';
}
pathlen = strlen(path) + strlen(relpath) + 2;
fullpath = (FAR char *)kmalloc(pathlen);
if (!fullpath)
{
/* Failed to allocate memory */
return (FAR char *)NULL;
}
/* Construct the full path */
sprintf(fullpath, "%s/%s", path, relpath);
/* Verify that a regular file exists at this path */
ret = stat(fullpath, &buf);;
if (ret == OK && S_ISREG(buf.st_mode))
{
return fullpath;
}
/* Failed to stat the file. Just free the allocated memory and
* continue to try the next path.
*/
kfree(fullpath);
}
/* We will not get here */
}
/****************************************************************************
* Name: exepath_release
*
* Description:
* Release all resources set aside by exepath_release when the handle value
* was created. The handle value is invalid on return from this function.
* Attempts to all exepath_next() or exepath_release() with such a 'stale'
* handle will result in undefined (i.e., not good) behavior.
*
* Input Parameters:
* handle - The handle value returned by exepath_init
*
* Returned Value:
* None
*
****************************************************************************/
void exepath_release(EXEPATH_HANDLE handle)
{
kfree(handle);
}
#endif /* !CONFIG_BINFMT_DISABLE && CONFIG_BINFMT_EXEPATH */

View File

@ -8,6 +8,10 @@ CONFIG_NUTTX_NEWCONFIG=y
# Build Setup
#
# CONFIG_EXPERIMENTAL is not set
CONFIG_HOST_LINUX=y
# CONFIG_HOST_OSX is not set
# CONFIG_HOST_WINDOWS is not set
# CONFIG_HOST_OTHER is not set
#
# Build Configuration
@ -83,7 +87,11 @@ CONFIG_BOARD_LOOPSPERMSEC=100
#
# CONFIG_ARCH_NOINTC is not set
# CONFIG_ARCH_DMA is not set
# CONFIG_ARCH_IRQPRIO is not set
# CONFIG_CUSTOM_STACK is not set
# CONFIG_ADDRENV is not set
# CONFIG_ARCH_STACKDUMP is not set
# CONFIG_ENDIAN_BIG is not set
#
# Board Settings
@ -165,7 +173,6 @@ CONFIG_PREALLOC_TIMERS=8
#
# Stack and heap information
#
# CONFIG_CUSTOM_STACK is not set
CONFIG_IDLETHREAD_STACKSIZE=4096
CONFIG_USERMAIN_STACKSIZE=4096
CONFIG_PTHREAD_STACK_MIN=256
@ -250,8 +257,10 @@ CONFIG_MM_REGIONS=1
# Binary Formats
#
# CONFIG_BINFMT_DISABLE is not set
# CONFIG_BINFMT_EXEPATH is not set
# CONFIG_NXFLAT is not set
# CONFIG_ELF is not set
# CONFIG_PIC is not set
# CONFIG_SYMTAB_ORDEREDBYNAME is not set
#
@ -274,9 +283,12 @@ CONFIG_ARCH_LOWPUTC=y
CONFIG_LIB_SENDFILE_BUFSIZE=512
# CONFIG_ARCH_ROMGETC is not set
# CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set
#
# Basic CXX Support
#
# CONFIG_C99_BOOL8 is not set
# CONFIG_HAVE_CXX is not set
# CONFIG_HAVE_CXXINITIALIZE is not set
# CONFIG_CXX_NEWLONG is not set
#
# Application Configuration
@ -302,6 +314,7 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
# CONFIG_EXAMPLES_HELLOXX is not set
# CONFIG_EXAMPLES_JSON is not set
# CONFIG_EXAMPLES_HIDKBD is not set
# CONFIG_EXAMPLES_KEYPADTEST is not set
# CONFIG_EXAMPLES_IGMP is not set
# CONFIG_EXAMPLES_LCDRW is not set
# CONFIG_EXAMPLES_MM is not set
@ -323,6 +336,8 @@ CONFIG_EXAMPLES_OSTEST=y
CONFIG_EXAMPLES_OSTEST_LOOPS=100
CONFIG_EXAMPLES_OSTEST_STACKSIZE=8192
CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=8
CONFIG_EXAMPLES_OSTEST_RR_RANGE=10000
CONFIG_EXAMPLES_OSTEST_RR_RUNS=10
# CONFIG_EXAMPLES_PASHELLO is not set
# CONFIG_EXAMPLES_PIPE is not set
# CONFIG_EXAMPLES_POLL is not set

View File

@ -54,6 +54,14 @@
/****************************************************************************
* Public Types
****************************************************************************/
/* EXEPATH_HANDLE is an opaque handle used to traverse the absolute paths
* assigned to the PATH environment variable.
*/
#if !defined(CONFIG_BINFMT_DISABLE) && defined(CONFIG_BINFMT_EXEPATH)
typedef FAR void *EXEPATH_HANDLE;
#endif
/* The type of one C++ constructor or destructor */
typedef FAR void (*binfmt_ctor_t)(void);
@ -100,12 +108,9 @@ struct binfmt_s
* Public Data
****************************************************************************/
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C" {
#else
#define EXTERN extern
extern "C"
{
#endif
/****************************************************************************
@ -125,7 +130,7 @@ extern "C" {
*
****************************************************************************/
EXTERN int register_binfmt(FAR struct binfmt_s *binfmt);
int register_binfmt(FAR struct binfmt_s *binfmt);
/****************************************************************************
* Name: unregister_binfmt
@ -140,7 +145,7 @@ EXTERN int register_binfmt(FAR struct binfmt_s *binfmt);
*
****************************************************************************/
EXTERN int unregister_binfmt(FAR struct binfmt_s *binfmt);
int unregister_binfmt(FAR struct binfmt_s *binfmt);
/****************************************************************************
* Name: load_module
@ -156,7 +161,7 @@ EXTERN int unregister_binfmt(FAR struct binfmt_s *binfmt);
*
****************************************************************************/
EXTERN int load_module(FAR struct binary_s *bin);
int load_module(FAR struct binary_s *bin);
/****************************************************************************
* Name: unload_module
@ -177,7 +182,7 @@ EXTERN int load_module(FAR struct binary_s *bin);
*
****************************************************************************/
EXTERN int unload_module(FAR const struct binary_s *bin);
int unload_module(FAR const struct binary_s *bin);
/****************************************************************************
* Name: exec_module
@ -192,7 +197,7 @@ EXTERN int unload_module(FAR const struct binary_s *bin);
*
****************************************************************************/
EXTERN int exec_module(FAR const struct binary_s *bin, int priority);
int exec_module(FAR const struct binary_s *bin, int priority);
/****************************************************************************
* Name: exec
@ -214,9 +219,92 @@ EXTERN int exec_module(FAR const struct binary_s *bin, int priority);
*
****************************************************************************/
EXTERN int exec(FAR const char *filename, FAR const char **argv,
int exec(FAR const char *filename, FAR const char **argv,
FAR const struct symtab_s *exports, int nexports);
/****************************************************************************
* Name: exepath_init
*
* Description:
* Initialize for the traversal of each value in the PATH variable. The
* usage is sequence is as follows:
*
* 1) Call exepath_init() to initialze for the traversal. exepath_init()
* will return an opaque handle that can then be provided to
* exepath_next() and exepath_release().
* 2) Call exepath_next() repeatedly to examine every file that lies
* in the directories of the PATH variable
* 3) Call exepath_release() to free resources set aside by exepath_init().
*
* Input Parameters:
* None
*
* Returned Value:
* On success, exepath_init() return a non-NULL, opaque handle that may
* subsequently be used in calls to exepath_next() and exepath_release().
* On error, a NULL handle value will be returned. The most likely cause
* of an error would be that the there is no value associated with the
* PATH variable.
*
****************************************************************************/
#if !defined(CONFIG_BINFMT_DISABLE) && defined(CONFIG_BINFMT_EXEPATH)
EXEPATH_HANDLE exepath_init(void);
#endif
/****************************************************************************
* Name: exepath_next
*
* Description:
* Traverse all possible values in the PATH variable in attempt to find
* the full path to an executable file when only a relative path is
* provided.
*
* Input Parameters:
* handle - The handle value returned by exepath_init
* relpath - The relative path to the file to be found.
*
* Returned Value:
* On success, a non-NULL pointer to a null-terminated string is provided.
* This is the full path to a file that exists in the file system. This
* function will verify that the file exists (but will not verify that it
* is marked executable).
*
* NOTE: The string pointer return in the success case points to allocated
* memory. This memory must be freed by the called by calling kfree().
*
* NULL is returned if no path is found to any file with the provided
* 'relpath' from any absolute path in the file variable. In this case,
* there is no point in calling exepath_next() further; exepath_release()
* must be called to release resources set aside by expath_init().
*
****************************************************************************/
#if !defined(CONFIG_BINFMT_DISABLE) && defined(CONFIG_BINFMT_EXEPATH)
FAR char *exepath_next(EXEPATH_HANDLE handle, FAR const char *relpath);
#endif
/****************************************************************************
* Name: exepath_release
*
* Description:
* Release all resources set aside by exepath_release when the handle value
* was created. The handle value is invalid on return from this function.
* Attempts to all exepath_next() or exepath_release() with such a 'stale'
* handle will result in undefined (i.e., not good) behavior.
*
* Input Parameters:
* handle - The handle value returned by exepath_init
*
* Returned Value:
* None
*
****************************************************************************/
#if !defined(CONFIG_BINFMT_DISABLE) && defined(CONFIG_BINFMT_EXEPATH)
void exepath_release(EXEPATH_HANDLE handle);
#endif
#undef EXTERN
#if defined(__cplusplus)
}

View File

@ -79,5 +79,3 @@ int clearenv(void)
#endif /* CONFIG_DISABLE_ENVIRON */

View File

@ -94,11 +94,11 @@ int env_release(FAR _TCB *ptcb)
{
/* Check the reference count on the environment structure */
if ( envp->ev_crefs <= 1)
if (envp->ev_crefs <= 1)
{
/* Decrementing the reference count will destroy the environment */
sched_free( envp ); /* plain free() should be fine here */
sched_free(envp);
}
else
{

View File

@ -44,6 +44,7 @@
#include <nuttx/config.h>
#include <sched.h>
#include <stdlib.h>
#include <debug.h>
#include <nuttx/init.h>
@ -129,6 +130,17 @@ int os_bringup(void)
#endif
int init_taskid;
/* Setup up the initial environment for the idle task. At present, this
* may consist of only the initial PATH variable. The PATH variable is
* (probably) not used by the IDLE task. However, the environment
* containing the PATH variable will be inherited by all of the threads
* created by the IDLE task.
*/
#if !defined(CONFIG_DISABLE_ENVIRON) && defined(CONFIG_PATH_INITIAL)
(void)setenv("PATH", CONFIG_PATH_INITIAL, 1);
#endif
/* Start the page fill worker kernel thread that will resolve page faults.
* This should always be the first thread started because it may have to
* resolve page faults in other threads
@ -190,5 +202,12 @@ int os_bringup(void)
(main_t)CONFIG_USER_ENTRYPOINT, (const char **)NULL);
#endif
ASSERT(init_taskid != ERROR);
/* We an save a few bytes by discarding the IDLE thread's environment. */
#if !defined(CONFIG_DISABLE_ENVIRON) && defined(CONFIG_PATH_INITIAL)
(void)clearenv();
#endif
return OK;
}

View File

@ -426,7 +426,9 @@ void os_start(void)
lib_initialize();
}
/* Create stdout, stderr, stdin */
/* Create stdout, stderr, stdin on the IDLE task. These will be
* inherited by all of the threads created by the IDLE task.
*/
(void)sched_setupidlefiles(&g_idletcb);