From ebc734d8e40e310bc94bd8321a70ce1b8ef5d5a9 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 10 Mar 2011 14:00:04 +0000 Subject: Experimental version of waitpid() git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3359 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/x86/src/qemu/qemu_vectors.S | 6 +- nuttx/configs/qemu-i486/README.txt | 27 ++-- nuttx/include/nuttx/sched.h | 6 +- nuttx/include/sys/types.h | 6 + nuttx/include/sys/wait.h | 118 +++++++++++++++ nuttx/sched/Makefile | 5 +- nuttx/sched/exit.c | 32 ++++- nuttx/sched/sched_waitpid.c | 252 +++++++++++++++++++++++++++++++++ 8 files changed, 437 insertions(+), 15 deletions(-) create mode 100644 nuttx/include/sys/wait.h create mode 100644 nuttx/sched/sched_waitpid.c (limited to 'nuttx') diff --git a/nuttx/arch/x86/src/qemu/qemu_vectors.S b/nuttx/arch/x86/src/qemu/qemu_vectors.S index a512e1f95..87412c21b 100755 --- a/nuttx/arch/x86/src/qemu/qemu_vectors.S +++ b/nuttx/arch/x86/src/qemu/qemu_vectors.S @@ -86,7 +86,7 @@ vector_isr\intno: cli /* Disable interrupts firstly. */ push $0 /* Push a dummy error code. */ push $\intno /* Push the interrupt number. */ - jmp isr_common /* Go to the common handler code. */ + jmp isr_common /* Go to the common ISR handler code. */ .endm /* This macro creates a stub for an ISR which passes it's own @@ -98,7 +98,7 @@ vector_isr\intno: vector_isr\intno: cli /* Disable interrupts firstly. */ push $\intno /* Push the interrupt number. */ - jmp isr_common /* Go to the common handler code. */ + jmp isr_common /* Go to the common ISR handler code. */ .endm /* This macro creates a stub for an IRQ - the first parameter is @@ -111,7 +111,7 @@ vector_irq\irqno: cli /* Disable interrupts firstly. */ push $0 /* Push a dummy error code. */ push $\intno /* Push the interrupt number. */ - jmp isr_common /* Go to the common handler code. */ + jmp irq_common /* Go to the common IRQ handler code. */ .endm /**************************************************************************** diff --git a/nuttx/configs/qemu-i486/README.txt b/nuttx/configs/qemu-i486/README.txt index 112a04a43..3476f09e5 100644 --- a/nuttx/configs/qemu-i486/README.txt +++ b/nuttx/configs/qemu-i486/README.txt @@ -9,13 +9,14 @@ Contents * QEMU - Building QEMU - - Cygwin Build Problems - - Running QEMU + - Cygwin Build Problems + - Running QEMU * Toolchains - Cygwin Buildroot Toolchain - - Buildroot Instructions + - Buildroot Instructions * Configurations - ostest + - nsh QEMU ==== @@ -47,18 +48,18 @@ Cygwin Build Problems Workaround: None known. It does not seem possible to build QEMU using the Cygwin gcc. - I tried editing configure. Removing the following line will allow QEMU to - configure: + I tried editing configure. Removing the following line will allow QEMU to + configure: QEMU_CFLAGS="-mno-cygwin $QEMU_CFLAGS" - However, it then fails later during the compilation phase. + However, it then fails later during the compilation phase. Recommendation: 1. Google for "qemu windows download" and download some pre-built QEMU - binaries. I found 0.14.0 here: http://dietpc.org/windows/qemu/, or - 2. Try building QEMU with MingGW (I understand that this is difficult). + binaries. I found 0.14.0 here: http://dietpc.org/windows/qemu/, or + 2. Try building QEMU with MingGW (I understand that this is difficult). NOTE: As of this writing, I have not been successful getting ANY pre-built version of QEMU to work successful; they all fail immediately with @@ -135,3 +136,13 @@ ostest cd /tools ./configure.sh qemu-i486/ostest + +nsh +--- + + Configures the NuttShell (nsh) located at examples/nsh. This + configuration may be selected as follows: + + cd /tools + ./configure.sh qemu-i486/nsh + diff --git a/nuttx/include/nuttx/sched.h b/nuttx/include/nuttx/sched.h index 027d00489..c5e061cb6 100644 --- a/nuttx/include/nuttx/sched.h +++ b/nuttx/include/nuttx/sched.h @@ -1,7 +1,7 @@ /******************************************************************************** * nuttx/sched.h * - * Copyright (C) 2007-2010 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2011 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -178,6 +178,10 @@ struct _TCB start_t start; /* Thread start function */ entry_t entry; /* Entry Point into the thread */ exitfunc_t exitfunc; /* Called if exit is called. */ +#ifdef CONFIG_SCHED_WAITPID /* Experimental */ + sem_t exitsem; /* Support for waitpid */ + int *stat_loc; /* Location to return exit status */ +#endif uint8_t sched_priority; /* Current priority of the thread */ #ifdef CONFIG_PRIORITY_INHERITANCE # if CONFIG_SEM_NNESTPRIO > 0 diff --git a/nuttx/include/sys/types.h b/nuttx/include/sys/types.h index 4be7d3527..736d2fb75 100644 --- a/nuttx/include/sys/types.h +++ b/nuttx/include/sys/types.h @@ -152,6 +152,12 @@ typedef uint16_t ino_t; typedef int pid_t; +/* id_t is a general identifier that can be used to contain at least a pid_t, + * uid_t, or gid_t. + */ + +typedef unsigned int id_t; + /* blkcnt_t and off_t are signed integer types. * * blkcnt_t is used for file block counts. diff --git a/nuttx/include/sys/wait.h b/nuttx/include/sys/wait.h new file mode 100644 index 000000000..559b922f3 --- /dev/null +++ b/nuttx/include/sys/wait.h @@ -0,0 +1,118 @@ +/**************************************************************************** + * include/sys/wait.h + * + * Copyright (C) 2011 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. + * + ****************************************************************************/ + +#ifndef __INCLUDE_SYS_WAIT_H +#define __INCLUDE_SYS_WAIT_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#ifdef CONFIG_SCHED_WAITPID + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/* The following are provided for analysis of returned status values. + * Encoded is as follows as 2 bytes of info(MS) then two bytes of code (LS). + * Code: + * 0 - Child has exited, info is the exit code. + * Other values - Not implemented + */ + +#define WEXITSTATUS(s) (((s) >> 8) & 0xff)/* Return exit status */ + +#define WIFEXITED(s) (((s) & 0xff) == 0) /* True: Child exited normally */ +#define WIFCONTINUED(s) (false) /* True: Child has been continued */ +#define WIFSIGNALED(s) (false) /* True: Child exited due to uncaught signal */ +#define WIFSTOPPED(s) (false) /* True: Child is currently stopped */ +#define WSTOPSIG(s) (false) /* Return signal number that caused process to stop */ +#define WTERMSIG(s) (false) /* Return signal number that caused process to terminate */ + +/* The following symbolic constants are possible values for the options + * argument to waitpi(1) (1) and/or waitid() (2), + */ + +#define WCONTINUED (1 << 0) /* Status for child that has been continued (1)(2) */ +#define WNOHANG (1 << 1) /* Do not wait if status not available (1) */ +#define WUNTRACED (1 << 2) /* Report status of stopped child process (1) */ + +#define WEXITED (1 << 3) /* Wait for processes that have exited (2) */ +#define WSTOPPED (1 << 4) /* Status for child stopped on signal (2) */ +#define WNOHANG (1 << 5) /* Return immediately if there are no children (2) */ +#define WNOWAIT (1 << 6) /* Keep the process in a waitable state (2) */ + +/**************************************************************************** + * Public Type Definitions + ****************************************************************************/ + +#ifndef __ASSEMBLY__ + +enum idtype_e +{ + P_PID = 1, + P_GID = 2, + P_ALL = 3 +}; +typedef enum idtype_e idtype_t; + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +EXTERN pid_t wait(int *stat_loc); +EXTERN int waitid(idtype_t idtype, id_t id, siginfo_t *siginfo, int options); +EXTERN pid_t waitpid(pid_t pid, int *stat_loc, int options); + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* CONFIG_SCHED_WAITPID */ +#endif /* __INCLUDE_SYS_WAIT_H */ diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile index 31e09f2aa..55dd15547 100644 --- a/nuttx/sched/Makefile +++ b/nuttx/sched/Makefile @@ -1,7 +1,7 @@ ############################################################################ # sched/Makefile # -# Copyright (C) 2007-2010 Gregory Nutt. All rights reserved. +# Copyright (C) 2007-2011 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -58,6 +58,9 @@ SCHED_SRCS = sched_setparam.c sched_setpriority.c sched_getparam.c \ ifeq ($(CONFIG_PRIORITY_INHERITANCE),y) SCHED_SRCS += sched_reprioritize.c endif +ifeq ($(CONFIG_SCHED_WAITPID),y) +SCHED_SRCS += sched_waitpid.c +endif ENV_SRCS = env_getenvironptr.c env_dup.c env_share.c env_release.c \ env_findvar.c env_removevar.c \ diff --git a/nuttx/sched/exit.c b/nuttx/sched/exit.c index 5302dade6..b1f743d97 100644 --- a/nuttx/sched/exit.c +++ b/nuttx/sched/exit.c @@ -1,7 +1,7 @@ /**************************************************************************** * sched/exit.c * - * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2008, 2011 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -93,6 +93,10 @@ void exit(int status) { _TCB *tcb = (_TCB*)g_readytorun.head; + /* Only the lower 8 bits of the exit status are used */ + + status &= 0xff; + /* Flush all streams (File descriptors will be closed when * the TCB is deallocated. */ @@ -101,6 +105,29 @@ void exit(int status) (void)lib_flushall(tcb->streams); #endif + /* Wakeup any tasks waiting for this task to exit */ + +#ifdef CONFIG_SCHED_WAITPID /* Experimental */ + while (tcb->exitsem.semcount < 0) + { + /* "If more than one thread is suspended in waitpid() awaiting + * termination of the same process, exactly one thread will return + * the process status at the time of the target process termination." + * Hmmm.. what do we return to the others? + */ + + if (tcb->stat_loc) + { + *tcb->stat_loc = status << 8; + tcb->stat_loc = NULL; + } + + /* Wake up the thread */ + + sem_post(&tcb->exitsem); + } +#endif + /* If an exit function was registered, call it now. */ if (tcb->exitfunc) { @@ -108,6 +135,7 @@ void exit(int status) (*tcb->exitfunc)(); } /* end if */ + /* Then "really" exit */ - _exit(status & 0377); + _exit(status); } diff --git a/nuttx/sched/sched_waitpid.c b/nuttx/sched/sched_waitpid.c new file mode 100644 index 000000000..6e544f2eb --- /dev/null +++ b/nuttx/sched/sched_waitpid.c @@ -0,0 +1,252 @@ +/***************************************************************************** + * sched/sched_waitpid.c + * + * Copyright (C) 2011 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 + +#include + +#include "os_internal.h" + +#ifdef CONFIG_SCHED_WAITPID /* Experimental */ + +/***************************************************************************** + * Private Functions + *****************************************************************************/ + +/***************************************************************************** + * Public Functions + *****************************************************************************/ + +/***************************************************************************** + * Function: sched_waitpid + * + * Description: + * + * The waitpid() functions will obtain status information pertaining to one + * of the caller's child processes. The waitpid() function will suspend + * execution of the calling thread until status information for one of the + * terminated child processes of the calling process is available, or until + * delivery of a signal whose action is either to execute a signal-catching + * function or to terminate the process. If more than one thread is suspended + * in waitpid() awaiting termination of the same process, exactly one thread + * will return the process status at the time of the target process + * termination. If status information is available prior to the call to + * waitpid(), return will be immediate. + * + * The pid argument specifies a set of child processes for which status is + * requested. The waitpid() function will only return the status of a child + * process from this set: + * + * - If pid is equal to (pid_t)-1, status is requested for any child process. + * In this respect, waitpid() is then equivalent to wait(). + * - If pid is greater than 0, it specifies the process ID of a single child + * process for which status is requested. + * - If pid is 0, status is requested for any child process whose process + * group ID is equal to that of the calling process. + * - If pid is less than (pid_t)-1, status is requested for any child process + * whose process group ID is equal to the absolute value of pid. + * + * The options argument is constructed from the bitwise-inclusive OR of zero + * or more of the following flags, defined in the header: + * + * WCONTINUED - The waitpid() function will report the status of any + * continued child process specified by pid whose status has not been + * reported since it continued from a job control stop. + * WNOHANG - The waitpid() function will not suspend execution of the + * calling thread if status is not immediately available for one of the + * child processes specified by pid. + * WUNTRACED - The status of any child processes specified by pid that are + * stopped, and whose status has not yet been reported since they stopped, + * will also be reported to the requesting process. + * + * If the calling process has SA_NOCLDWAIT set or has SIGCHLD set to + * SIG_IGN, and the process has no unwaited-for children that were + * transformed into zombie processes, the calling thread will block until all + * of the children of the process containing the calling thread terminate, and + * waitpid() will fail and set errno to ECHILD. + * + * If waitpid() returns because the status of a child process is available, + * these functions will return a value equal to the process ID of the child + * process. In this case, if the value of the argument stat_loc is not a + * null pointer, information will be stored in the location pointed to by + * stat_loc. The value stored at the location pointed to by stat_loc will be + * 0 if and only if the status returned is from a terminated child process + * that terminated by one of the following means: + * + * 1. The process returned 0 from main(). + * 2. The process called _exit() or exit() with a status argument of 0. + * 3. The process was terminated because the last thread in the process terminated. + * + * Regardless of its value, this information may be interpreted using the + * following macros, which are defined in and evaluate to + * integral expressions; the stat_val argument is the integer value pointed + * to by stat_loc. + * + * WIFEXITED(stat_val) - Evaluates to a non-zero value if status was + * returned for a child process that terminated normally. + * WEXITSTATUS(stat_val) - If the value of WIFEXITED(stat_val) is non-zero, + * this macro evaluates to the low-order 8 bits of the status argument + * that the child process passed to _exit() or exit(), or the value the + * child process returned from main(). + * WIFSIGNALED(stat_val) - Evaluates to a non-zero value if status was + * returned for a child process that terminated due to the receipt of a + * signal that was not caught (see ). + * WTERMSIG(stat_val) - If the value of WIFSIGNALED(stat_val) is non-zero, + * this macro evaluates to the number of the signal that caused the + * termination of the child process. + * WIFSTOPPED(stat_val) - Evaluates to a non-zero value if status was + * returned for a child process that is currently stopped. + * WSTOPSIG(stat_val) - If the value of WIFSTOPPED(stat_val) is non-zero, + * this macro evaluates to the number of the signal that caused the child + * process to stop. + * WIFCONTINUED(stat_val) - Evaluates to a non-zero value if status was + * returned for a child process that has continued from a job control stop. + * + * Parameters: + * pid - The task ID of the thread to waid for + * stat_loc - The location to return the exit status + * options - ignored + * + * Return Value: + * If waitpid() returns because the status of a child process is available, + * it will return a value equal to the process ID of the child process for + * which status is reported. + * + * If waitpid() returns due to the delivery of a signal to the calling + * process, -1 will be returned and errno set to EINTR. + * + * If waitpid() was invoked with WNOHANG set in options, it has at least + * one child process specified by pid for which status is not available, and + * status is not available for any process specified by pid, 0 is returned. + * + * Otherwise, (pid_t)-1 will be returned, and errno set to indicate the error: + * + * ECHILD - The process specified by pid does not exist or is not a child of + * the calling process, or the process group specified by pid does not exist + * or does not have any member process that is a child of the calling process. + * EINTR - The function was interrupted by a signal. The value of the location + * pointed to by stat_loc is undefined. + * EINVAL - The options argument is not valid. + * + * Assumptions: + * + *****************************************************************************/ + +/***************************************************************************/ +/* NOTE: This is a partially functional, experimental version of waitpid() */ +/***************************************************************************/ + +pid_t waitpid(pid_t pid, int *stat_loc, int options) +{ + _TCB *tcb = sched_gettcb(pid); + bool mystat; + int err; + int ret; + + /* Disable pre-emption so that nothing changes in the following tests */ + + sched_lock(); + if (!tcb) + { + err = ECHILD; + goto errout_with_errno; + } + + /* None of the options are supported */ + +#ifdef CONFIG_DEBUG + if (stat_loc == NULL) + { + err = EINVAL; + goto errout_with_errno; + } + + if (options != 0) + { + err = ENOSYS; + goto errout_with_errno; + } +#endif + + /* "If more than one thread is suspended in waitpid() awaiting termination of + * the same process, exactly one thread will return the process status at the + * time of the target process termination." Hmmm.. what do we return to the + * others? + */ + + if (tcb->stat_loc == NULL) + { + tcb->stat_loc = stat_loc; + mystat = true; + } + + /* Then wait for the task to exit */ + + ret = sem_wait(&tcb->exitsem); + if (ret < 0) + { + /* Unlock pre-emption and return the ERROR (sem_wait has already set + * the errno). Handle the awkward case of whether or not we need to + * nullify the stat_loc value. + */ + + if (mystat) + { + tcb->stat_loc = NULL; + } + goto errout; + } + + /* On success, return the PID */ + + sched_unlock(); + return pid; + +errout_with_errno: + errno = err; +errout: + sched_unlock(); + return ERROR; +} + +#endif /* CONFIG_SCHED_WAITPID */ -- cgit v1.2.3