Add file action logic which will eventually be needed to support posix_spawn()

git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5500 42af7a65-404d-4744-a932-0658087f49c3
This commit is contained in:
patacongo 2013-01-09 21:31:36 +00:00
parent d844f61f8a
commit 44fdf6fc7a
11 changed files with 735 additions and 12 deletions

View File

@ -3896,4 +3896,5 @@
* arch/arm/src/lm: Rename the arch/arm/src/lm3s directory to
arch/arm/src/lm so that is can support other members of the
Stellaris family.
* libc/spawn: Add file action interfaces needed by posix_spawn().

View File

@ -90,6 +90,7 @@ CONFIG_BOARD_LOOPSPERMSEC=100
# CONFIG_ARCH_IRQPRIO is not set
# CONFIG_CUSTOM_STACK is not set
# CONFIG_ADDRENV is not set
# CONFIG_ARCH_HAVE_VFORK is not set
# CONFIG_ARCH_STACKDUMP is not set
# CONFIG_ENDIAN_BIG is not set
@ -266,6 +267,10 @@ CONFIG_MM_REGIONS=1
#
# Library Routines
#
#
# Standard C Library Options
#
CONFIG_STDIO_BUFFER_SIZE=1024
CONFIG_STDIO_LINEBUFFER=y
CONFIG_NUNGET_CHARS=2
@ -277,6 +282,7 @@ CONFIG_LIB_HOMEDIR="/"
# CONFIG_EOL_IS_LF is not set
# CONFIG_EOL_IS_BOTH_CRLF is not set
CONFIG_EOL_IS_EITHER_CRLF=y
# CONFIG_LIBC_EXECFUNCS is not set
# CONFIG_LIBC_STRERROR is not set
# CONFIG_LIBC_PERROR_STDOUT is not set
CONFIG_ARCH_LOWPUTC=y
@ -284,6 +290,11 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
# CONFIG_ARCH_ROMGETC is not set
# CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set
#
# Non-standard Helper Functions
#
# CONFIG_LIB_KBDCODEC is not set
#
# Basic CXX Support
#
@ -295,7 +306,7 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
#
#
# Named Applications
# Built-In Applications
#
# CONFIG_BUILTIN is not set
@ -356,7 +367,6 @@ CONFIG_EXAMPLES_OSTEST_RR_RUNS=10
# CONFIG_EXAMPLES_USBMSC is not set
# CONFIG_EXAMPLES_USBTERM is not set
# CONFIG_EXAMPLES_WATCHDOG is not set
# CONFIG_EXAMPLES_WLAN is not set
#
# Interpreters

View File

@ -33,14 +33,16 @@
*
****************************************************************************/
#ifndef __INCLUDE_LIBGEN_H
#define __INCLUDE_LIBGEN_H
#ifndef __INCLUDE_SPAWN_H
#define __INCLUDE_SPAWN_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <sys/types.h>
#include <signal.h>
/****************************************************************************
@ -67,15 +69,23 @@
struct posix_spawnattr_s
{
/* To be provided */
uint8_t flags;
uint8_t priority;
pid_t group;
sigset_t sigset;
};
typedef struct posix_spawnattr_s posix_spawnattr_t;
struct posix_spawn_file_actions_s
{
/* To be provided */
};
typedef struct posix_spawn_file_actions_s posix_spawn_file_actions_t;
/* posix_spawn_file_actions_addclose(), posix_spawn_file_actions_adddup2(),
* and posix_spawn_file_actions_addopen() will allocate memory and append
* a new file action to an instance of posix_spawn_file_actions_t. The
* internal representation of these structures is not exposed to the user.
* The user need only know that the size sizeof(posix_spawn_file_actions_t)
* will hold a pointer to data.
*/
typedef FAR void *posix_spawn_file_actions_t;
/****************************************************************************
* Public Function Prototypes
@ -134,4 +144,4 @@ int posix_spawnattr_setsigmask(FAR posix_spawnattr_t *,
}
#endif
#endif /* __INCLUDE_LIBGEN_H */
#endif /* __INCLUDE_SPAWN_H */

View File

@ -37,7 +37,8 @@
ifeq ($(CONFIG_LIBC_EXECFUNCS),y)
CSRCS +=
CSRCS += lib_psfa_addaction.c lib_psfa_addclose.c lib_psfa_adddup2.c
CSRCS += lib_psfa_addopen.c lib_psfa_destroy.c lib_psfa_init.c
# Add the spawn directory to the build

View File

@ -0,0 +1,91 @@
/****************************************************************************
* libc/string/lib_psfa_addaction.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 <spawn.h>
#include "spawn/spawn.h"
/****************************************************************************
* Global Functions
****************************************************************************/
/****************************************************************************
* Name: add_file_action
*
* Description:
* Add the file action to the end for the file action list.
*
* Input Parameters:
* file_actions - The head of the file action list.
* entry - The file action to be added
*
* Returned Value:
* None
*
****************************************************************************/
void add_file_action(FAR posix_spawn_file_actions_t *file_actions,
FAR struct spawn_general_file_action_s *entry)
{
FAR struct spawn_general_file_action_s *prev;
FAR struct spawn_general_file_action_s *next;
/* Find the end of the list */
for (prev = NULL, next = (FAR struct spawn_general_file_action_s *)*file_actions;
next;
prev = next, next = next->flink);
/* Here next is NULL and prev points to the last entry in the list (or
* is NULL if the list is empty).
*/
if (prev)
{
prev->flink = entry;
}
else
{
*file_actions = (posix_spawn_file_actions_t)entry;
}
entry->flink = NULL;
}

View File

@ -0,0 +1,100 @@
/****************************************************************************
* libc/string/lib_psfa_addclose.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 <spawn.h>
#include <assert.h>
#include <errno.h>
#include "spawn/spawn.h"
/****************************************************************************
* Global Functions
****************************************************************************/
/****************************************************************************
* Name: posix_spawn_file_actions_addclose
*
* Description:
* The posix_spawn_file_actions_addclose() function adds a close operation
* to the list of operations associated with the object referenced by
* file_actions, for subsequent use in a call to posix_spawn(2) or
* posix_spawnp(2). The descriptor referred to by fd is closed as if
* close() had been called on it prior to the new child process starting
* execution.
*
* Input Parameters:
* file_actions - The posix_spawn_file_actions_t to append the action.
* fd - The file descriptor to be closed.
*
* Returned Value:
* On success, these functions return 0; on failure they return an error
* number from <errno.h>.
*
****************************************************************************/
int posix_spawn_file_actions_addclose(FAR posix_spawn_file_actions_t *file_actions,
int fd)
{
FAR struct spawn_close_file_action_s *entry;
DEBUGASSERT(file_actions && fd >= 0 && fd < CONFIG_NFILE_DESCRIPTORS);
/* Allocate the action list entry */
entry = (FAR struct spawn_close_file_action_s *)
zalloc(sizeof(struct spawn_close_file_action_s));
if (!entry)
{
return ENOMEM;
}
/* Initialize the file action entry */
entry->action = SPAWN_FILE_ACTION_CLOSE;
entry->fd = fd;
/* And add it to the file action list */
add_file_action(file_actions, (FAR struct spawn_general_file_action_s *)entry);
return OK;
}

View File

@ -0,0 +1,104 @@
/****************************************************************************
* libc/string/lib_psfa_adddup2.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 <spawn.h>
#include <assert.h>
#include <errno.h>
#include "spawn/spawn.h"
/****************************************************************************
* Global Functions
****************************************************************************/
/****************************************************************************
* Name: posix_spawn_file_actions_adddup2
*
* Description:
* The posix_spawn_file_actions_adddup2() function adds a dup2 operation to
* the list of operations associated with the object referenced by
* file_actions, for subsequent use in a call to posix_spawn(2) or
* posix_spawnp(2). The descriptor referred to by fd2 is created as
* if dup2() had been called on fd1 prior to the new child process
* starting execution.
*
* Input Parameters:
* file_actions - The posix_spawn_file_actions_t to append the action.
* fd1 - The first file descriptor to be argument to dup2.
* fd2 - The first file descriptor to be argument to dup2.
*
* Returned Value:
* On success, these functions return 0; on failure they return an error
* number from <errno.h>.
*
****************************************************************************/
int posix_spawn_file_actions_adddup2(FAR posix_spawn_file_actions_t *file_actions,
int fd1, int fd2)
{
FAR struct spawn_dup2_file_action_s *entry;
DEBUGASSERT(file_actions &&
fd1 >= 0 && fd1 < CONFIG_NFILE_DESCRIPTORS &&
fd2 >= 0 && fd2 < CONFIG_NFILE_DESCRIPTORS);
/* Allocate the action list entry */
entry = (FAR struct spawn_dup2_file_action_s *)
zalloc(sizeof(struct spawn_close_file_action_s));
if (!entry)
{
return ENOMEM;
}
/* Initialize the file action entry */
entry->action = SPAWN_FILE_ACTION_DUP2;
entry->fd1 = fd1;
entry->fd2 = fd2;
/* And add it to the file action list */
add_file_action(file_actions, (FAR struct spawn_general_file_action_s *)entry);
return OK;
}

View File

@ -0,0 +1,119 @@
/****************************************************************************
* libc/string/lib_psfa_addopen.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 <string.h>
#include <spawn.h>
#include <assert.h>
#include <errno.h>
#include "spawn/spawn.h"
/****************************************************************************
* Global Functions
****************************************************************************/
/****************************************************************************
* Name: posix_spawn_file_actions_addopen
*
* Description:
* The posix_spawn_file_actions_addopen() function adds an open operation
* to the list of operations associated with the object referenced by
* file_actions, for subsequent use in a call to posix_spawn(2) or
* posix_spawnp(2). The descriptor referred to by fd is opened using
* the path, oflag, and mode arguments as if open() had been called on it
* prior to the new child process starting execution. The string path is
* copied by the posix_spawn_file_actions_addopen() function during this
* process, so storage need not be persistent in the caller.
*
* Input Parameters:
* file_actions - The posix_spawn_file_actions_t to append the action.
* fd - The path to be opened.
* path - The first file descriptor to be argument to dup2.
* oflags - Open flags
* mode - File creation mode
*
* Returned Value:
* On success, these functions return 0; on failure they return an error
* number from <errno.h>.
*
****************************************************************************/
int posix_spawn_file_actions_addopen(FAR posix_spawn_file_actions_t *file_actions,
int fd, FAR const char *path, int oflags,
mode_t mode)
{
FAR struct spawn_open_file_action_s *entry;
size_t len;
size_t alloc;
DEBUGASSERT(file_actions && path &&
fd >= 0 && fd < CONFIG_NFILE_DESCRIPTORS);
/* Get the size of the action including storage for the path plus its NUL
* terminating character.
*/
len = strlen(path);
alloc = SIZEOF_OPEN_FILE_ACTION_S(len);
/* Allocate the action list entry of this size */
entry = (FAR struct spawn_open_file_action_s *)zalloc(alloc);
if (!entry)
{
return ENOMEM;
}
/* Initialize the file action entry */
entry->action = SPAWN_FILE_ACTION_OPEN;
entry->fd = fd;
entry->oflags = oflags;
entry->mode = mode;
strncpy(entry->path, path, len+1);
/* And add it to the file action list */
add_file_action(file_actions, (FAR struct spawn_general_file_action_s *)entry);
return OK;
}

View File

@ -0,0 +1,96 @@
/****************************************************************************
* libc/string/lib_psfa_destroy.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 <stdlib.h>
#include <spawn.h>
#include <assert.h>
#include "spawn/spawn.h"
/****************************************************************************
* Global Functions
****************************************************************************/
/****************************************************************************
* Name: posix_spawn_file_actions_destroy
*
* Description:
* The posix_spawn_file_actions_destroy() function destroys the object
* referenced by file_actions which was previously intialized by
* posix_spawn_file_actions_init(), returning any resources obtained at the
* time of initialization to the system for subsequent reuse. A
* posix_spawn_file_actions_t may be reinitialized after having been
* destroyed, but must not be reused after destruction, unless it has been
* reinitialized.
*
* Input Parameters:
* file_actions - The posix_spawn_file_actions_t to be destroyed.
*
* Returned Value:
* On success, these functions return 0; on failure they return an error
* number from <errno.h>.
*
****************************************************************************/
int posix_spawn_file_actions_destroy(FAR posix_spawn_file_actions_t *file_actions)
{
FAR struct spawn_general_file_action_s *curr;
FAR struct spawn_general_file_action_s *next;
DEBUGASSERT(file_actions);
/* Destroy each file action, one at a time */
for (curr = (FAR struct spawn_general_file_action_s *)*file_actions;
curr;
curr = next)
{
/* Get the pointer to the next element before destroying the current one */
next = curr->flink;
free(curr);
}
/* Mark the list empty */
*file_actions = NULL;
return OK;
}

View File

@ -0,0 +1,70 @@
/****************************************************************************
* libc/string/lib_psfa_init.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 <spawn.h>
/****************************************************************************
* Global Functions
****************************************************************************/
/****************************************************************************
* Name: posix_spawn_file_actions_init
*
* Description:
* The posix_spawn_file_actions_init() function initializes the object
* referenced by file_actions, to an empty set of file actions for
* subsequent use in a call to posix_spawn(2) or posix_spawnp(2).
*
* Input Parameters:
* file_actions - The address of the posix_spawn_file_actions_t to be
* initialized.
*
* Returned Value:
* On success, these functions return 0; on failure they return an error
* number from <errno.h>.
*
****************************************************************************/
int posix_spawn_file_actions_init(FAR posix_spawn_file_actions_t *file_actions)
{
file_actions = NULL;
return OK;
}

121
nuttx/libc/spawn/spawn.h Normal file
View File

@ -0,0 +1,121 @@
/****************************************************************************
* libc/spawn/spawn.h
*
* 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.
*
****************************************************************************/
#ifndef __LIBC_SPAWN_SPAWN_H
#define __LIBC_SPAWN_SPAWN_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <spawn.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Type Definitions
****************************************************************************/
/* This enumerator identifies a file action */
enum spawn_file_actions_e
{
SPAWN_FILE_ACTION_NONE = 0,
SPAWN_FILE_ACTION_CLOSE,
SPAWN_FILE_ACTION_DUP2,
SPAWN_FILE_ACTION_OPEN
};
/* posix_spawn_file_actions_addclose(), posix_spawn_file_actions_adddup2(),
* and posix_spawn_file_actions_addopen() will allocate memory and append
* a new file action to an instance of posix_spawn_file_actions_t. The
* internal representation of these structures are defined below:
*/
struct spawn_general_file_action_s
{
FAR struct spawn_general_file_action_s *flink; /* Supports a singly linked list */
enum spawn_file_actions_e action; /* A member of enum spawn_file_actions_e */
};
struct spawn_close_file_action_s
{
FAR struct spawn_general_file_action_s *flink; /* Supports a singly linked list */
enum spawn_file_actions_e action; /* SPAWN_FILE_ACTION_CLOSE */
int fd; /* The file descriptor to close */
};
struct spawn_dup2_file_action_s
{
FAR struct spawn_general_file_action_s *flink; /* Supports a singly linked list */
enum spawn_file_actions_e action; /* SPAWN_FILE_ACTION_DUP2 */
int fd1; /* The first file descriptor for dup2() */
int fd2; /* The second file descriptor for dup2() */
};
struct spawn_open_file_action_s
{
FAR struct spawn_general_file_action_s *flink; /* Supports a singly linked list */
enum spawn_file_actions_e action; /* SPAWN_FILE_ACTION_OPEN */
int fd; /* The file descriptor after opening */
int oflags; /* Open flags */
mode_t mode; /* File creation mode */
char path[1]; /* Start of the path to be
* opened */
};
#define SIZEOF_OPEN_FILE_ACTION_S(n) \
(sizeof(struct spawn_open_file_action_s) + (n))
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
#ifdef __cplusplus
extern "C"
{
#endif
void add_file_action(FAR posix_spawn_file_actions_t *file_action,
FAR struct spawn_general_file_action_s *entry);
#ifdef __cplusplus
}
#endif
#endif /* __LIBC_SPAWN_SPAWN_H */