From b3f3dd123c181fe851f0a9756bed7acd4ba4ef7d Mon Sep 17 00:00:00 2001 From: patacongo Date: Sun, 13 Jan 2013 18:53:00 +0000 Subject: [PATCH] Use SIGCHLD with waitpid(); implemented wait() and waitid() git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5515 42af7a65-404d-4744-a932-0658087f49c3 --- apps/ChangeLog.txt | 3 +- apps/examples/ostest/Makefile | 4 + apps/examples/ostest/ostest.h | 42 ++-- apps/examples/ostest/ostest_main.c | 8 + apps/examples/ostest/waitpid.c | 269 +++++++++++++++++++++ nuttx/ChangeLog | 7 + nuttx/Documentation/NuttX.html | 8 +- nuttx/Documentation/NuttxPortingGuide.html | 10 +- nuttx/Documentation/NuttxUserGuide.html | 181 +++++++++++++- nuttx/TODO | 13 +- nuttx/configs/README.txt | 16 +- nuttx/configs/sim/ostest/defconfig | 2 +- nuttx/include/nuttx/sched.h | 5 +- nuttx/include/sys/types.h | 4 +- nuttx/include/sys/wait.h | 10 +- nuttx/sched/Kconfig | 14 +- nuttx/sched/Makefile | 5 +- nuttx/sched/os_internal.h | 6 +- nuttx/sched/sched_wait.c | 90 +++++++ nuttx/sched/sched_waitid.c | 256 ++++++++++++++++++++ nuttx/sched/sched_waitpid.c | 194 +++++++++++++-- nuttx/sched/task_exithook.c | 24 +- nuttx/sched/task_setup.c | 3 + 23 files changed, 1079 insertions(+), 95 deletions(-) create mode 100644 apps/examples/ostest/waitpid.c create mode 100644 nuttx/sched/sched_wait.c create mode 100644 nuttx/sched/sched_waitid.c diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt index 65d4d6134e..70381a79da 100644 --- a/apps/ChangeLog.txt +++ b/apps/ChangeLog.txt @@ -464,4 +464,5 @@ * apps/exampes/posix_spawn: Added a test of poxis_spawn(). * apps/examples/ostest: Extend signal handler test to catch death-of-child signals (SIGCHLD). - + * apps/examples/ostest/waitpid.c: Add a test for waitpid(), waitid(), + and wait(). diff --git a/apps/examples/ostest/Makefile b/apps/examples/ostest/Makefile index b7ba9a9a87..5a8ff72931 100644 --- a/apps/examples/ostest/Makefile +++ b/apps/examples/ostest/Makefile @@ -52,6 +52,10 @@ ifeq ($(CONFIG_ARCH_FPU),y) CSRCS += fpu.c endif +ifeq ($(CONFIG_SCHED_WAITPID),y) +CSRCS += waitpid.c +endif + ifneq ($(CONFIG_DISABLE_PTHREAD),y) CSRCS += cancel.c cond.c mutex.c sem.c barrier.c ifneq ($(CONFIG_RR_INTERVAL),0) diff --git a/apps/examples/ostest/ostest.h b/apps/examples/ostest/ostest.h index bc46a3860c..5217f0a0cb 100644 --- a/apps/examples/ostest/ostest.h +++ b/apps/examples/ostest/ostest.h @@ -105,68 +105,74 @@ /* dev_null.c ***************************************************************/ -extern int dev_null(void); +int dev_null(void); /* fpu.c ********************************************************************/ -extern void fpu_test(void); +void fpu_test(void); + +/* waitpid.c ****************************************************************/ + +#ifdef CONFIG_SCHED_WAITPID +int waitpid_test(void); +#endif /* mutex.c ******************************************************************/ -extern void mutex_test(void); +void mutex_test(void); /* rmutex.c ******************************************************************/ -extern void recursive_mutex_test(void); +void recursive_mutex_test(void); /* sem.c ********************************************************************/ -extern void sem_test(void); +void sem_test(void); /* cond.c *******************************************************************/ -extern void cond_test(void); +void cond_test(void); /* mqueue.c *****************************************************************/ -extern void mqueue_test(void); +void mqueue_test(void); /* timedmqueue.c ************************************************************/ -extern void timedmqueue_test(void); +void timedmqueue_test(void); /* cancel.c *****************************************************************/ -extern void cancel_test(void); +void cancel_test(void); /* timedwait.c **************************************************************/ -extern void timedwait_test(void); +void timedwait_test(void); /* sighand.c ****************************************************************/ -extern void sighand_test(void); +void sighand_test(void); /* posixtimers.c ************************************************************/ -extern void timer_test(void); +void timer_test(void); /* roundrobin.c *************************************************************/ -extern void rr_test(void); +void rr_test(void); /* barrier.c ****************************************************************/ -extern void barrier_test(void); +void barrier_test(void); /* prioinherit.c ************************************************************/ -extern void priority_inheritance(void); +void priority_inheritance(void); /* vfork.c ******************************************************************/ #ifdef CONFIG_ARCH_HAVE_VFORK -extern int vfork_test(void); +int vfork_test(void); #endif /* APIs exported (conditionally) by the OS specifically for testing of @@ -174,8 +180,8 @@ extern int vfork_test(void); */ #if defined(CONFIG_DEBUG) && defined(CONFIG_PRIORITY_INHERITANCE) && defined(CONFIG_SEM_PHDEBUG) -extern void sem_enumholders(FAR sem_t *sem); -extern int sem_nfreeholders(void); +void sem_enumholders(FAR sem_t *sem); +int sem_nfreeholders(void); #else # define sem_enumholders(sem) # define sem_nfreeholders() diff --git a/apps/examples/ostest/ostest_main.c b/apps/examples/ostest/ostest_main.c index ca44353c3d..aab1ff0457 100644 --- a/apps/examples/ostest/ostest_main.c +++ b/apps/examples/ostest/ostest_main.c @@ -301,6 +301,14 @@ static int user_main(int argc, char *argv[]) check_test_memory_usage(); #endif +#ifdef CONFIG_SCHED_WAITPID + /* Check waitpid() and friends */ + + printf("\nuser_main: waitpid test\n"); + waitpid_test(); + check_test_memory_usage(); +#endif + #ifndef CONFIG_DISABLE_PTHREAD /* Verify pthreads and pthread mutex */ diff --git a/apps/examples/ostest/waitpid.c b/apps/examples/ostest/waitpid.c new file mode 100644 index 0000000000..e53b49213a --- /dev/null +++ b/apps/examples/ostest/waitpid.c @@ -0,0 +1,269 @@ +/**************************************************************************** + * examples/ostest/waitpid.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 +#include +#include + +#include "ostest.h" + +#ifdef CONFIG_SCHED_WAITPID + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define RETURN_STATUS 14 +#define NCHILDREN 3 +#define PRIORITY 100 + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static int g_waitpids[NCHILDREN]; + +/**************************************************************************** + * Priviate Functions + ****************************************************************************/ + +static int waitpid_main(int argc, char *argv[]) +{ + pid_t me = getpid(); + + printf("waitpid_main: PID %d Started\n", me); + sleep(3); + printf("waitpid_main: PID %d exitting with result=%d\n", me, RETURN_STATUS); + return RETURN_STATUS; +} + +static void waitpid_start_children(void) +{ + int ret; + int i; + + for (i = 0; i < NCHILDREN; i++) + { + ret = TASK_CREATE("waitpid", PRIORITY, STACKSIZE, waitpid_main, NULL); + if (ret < 0) + { + printf("waitpid_start_child: ERROR Failed to start user_main\n"); + } + else + { + printf("waitpid_start_child: Started waitpid_main at PID=%d\n", ret); + } + + g_waitpids[i] = ret; + } +} + +static void waitpid_last(void) +{ + int stat_loc; + int ret; + + printf("waitpid_last: Waiting for PID=%d with waitpid()\n", + g_waitpids[NCHILDREN-1]); + + ret = (int)waitpid(g_waitpids[NCHILDREN-1], &stat_loc, 0); + if (ret < 0) + { + int errcode = errno; + printf("waitpid_last: ERROR: PID %d waitpid failed: %d\n", + g_waitpids[NCHILDREN-1], errcode); + } + else if (stat_loc != RETURN_STATUS) + { + printf("waitpid_last: ERROR: PID %d return status is %d, expected %d\n", + g_waitpids[NCHILDREN-1], stat_loc, RETURN_STATUS); + } + else + { + printf("waitpid_last: PID %d waitpid succeeded with stat_loc=%d\n", + g_waitpids[NCHILDREN-1], stat_loc); + } +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +int waitpid_test(void) +{ +#ifdef CONFIG_SCHED_HAVE_PARENT + siginfo_t info; +#endif + int stat_loc; + int ret; + + /* Start the children and wait for first one to complete */ + + printf("\nTest waitpid()\n"); + waitpid_start_children(); + + printf("waitpid_test: Waiting for PID=%d with waitpid()\n", g_waitpids[0]); + ret = (int)waitpid(g_waitpids[0], &stat_loc, 0); + if (ret < 0) + { + int errcode = errno; + printf("waitpid_test: ERROR: PID %d waitpid failed: %d\n", + g_waitpids[0], errcode); + } + else if (ret != g_waitpids[0]) + { + printf("waitpid_test: ERROR: PID %d wait returned PID %d\n", + g_waitpids[0], ret); + } + else if (stat_loc != RETURN_STATUS) + { + printf("waitpid_test: ERROR: PID %d return status is %d, expected %d\n", + g_waitpids[0], stat_loc, RETURN_STATUS); + } + else + { + printf("waitpid_test: PID %d waitpid succeeded with stat_loc=%d\n", + g_waitpids[0], stat_loc); + } + + /* Wait a big to make sure that the other threads complete */ + + waitpid_last(); + sleep(1); + +#ifdef CONFIG_SCHED_HAVE_PARENT + /* Start the children and wait for first one to complete */ + + printf("\nTest waitid(P_PID)\n"); + waitpid_start_children(); + + printf("waitpid_test: Waiting for PID=%d with waitid()\n", g_waitpids[0]); + ret = waitid(P_PID, (id_t)g_waitpids[0], &info, WEXITED); + if (ret < 0) + { + int errcode = errno; + printf("waitpid_test: ERROR: PID %d waitid failed: %d\n", + g_waitpids[0], errcode); + } + else if (info.si_pid != g_waitpids[0]) + { + printf("waitpid_test: ERROR: PID %d waitid returned PID %d\n", + g_waitpids[0], info.si_pid); + } + else if (info.si_status != RETURN_STATUS) + { + printf("waitpid_test: ERROR: PID %d return status is %d, expected %d\n", + info.si_pid, info.si_status, RETURN_STATUS); + } + else + { + printf("waitpid_test: waitid PID %d succeeded with si_status=%d\n", + info.si_pid, info.si_status); + } + + /* Wait a big to make sure that the other threads complete */ + + waitpid_last(); + sleep(1); + + /* Start the children and wait for any one to complete */ + + printf("\nTest waitid(P_ALL)\n"); + waitpid_start_children(); + + printf("waitpid_test: Waiting for any child with waitid()\n"); + ret = waitid(P_ALL, 0, &info, WEXITED); + if (ret < 0) + { + int errcode = errno; + printf("waitpid_test: ERROR: waitid failed: %d\n", errcode); + } + else if (info.si_status != RETURN_STATUS) + { + printf("waitpid_test: ERROR: PID %d return status is %d, expected %d\n", + info.si_pid, info.si_status, RETURN_STATUS); + } + else + { + printf("waitpid_test: PID %d waitid succeeded with si_status=%d\n", + info.si_pid, info.si_status); + } + + /* Wait a big to make sure that the other threads complete */ + + waitpid_last(); + sleep(1); + + /* Start the children and wait for first one to complete */ + + printf("\nTest wait()\n"); + waitpid_start_children(); + + printf("waitpid_test: Waiting for any child with wait()\n"); + ret = (int)wait(&stat_loc); + if (ret < 0) + { + int errcode = errno; + printf("waitpid_test: ERROR: wait failed: %d\n", errcode); + } + else if (stat_loc != RETURN_STATUS) + { + printf("waitpid_test: ERROR: PID %d return status is %d, expected %d\n", + ret, stat_loc, RETURN_STATUS); + } + else + { + printf("waitpid_test: PID %d wait succeeded with stat_loc=%d\n", + ret, stat_loc); + } + + /* Wait a big to make sure that the other threads complete */ + + waitpid_last(); + sleep(1); +#endif + + return 0; +} + +#endif /* CONFIG_SCHED_WAITPID */ diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 7deb9fa946..e8d4f7309c 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3922,3 +3922,10 @@ which decrements the lockcount on the wrong TCB. The failure case that I saw was that pre-emption got disabled in the IDLE thread, locking up the whole system. + * sched/sched_waitpid.c: Use SIGCHLD instead of a semaphore. This + is a much more spec-compliant implemenation. However, there are + some issues with overruning signals because NuttX does not support + queueing of signals (POSIX does not require it). I think it may + need to. + * sched/sched_waitid.c and sched_wait.c: Add support for waitid() + and wait(). See issues with waitpid() above. diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html index f6e9a41bae..22651de79e 100644 --- a/nuttx/Documentation/NuttX.html +++ b/nuttx/Documentation/NuttX.html @@ -286,7 +286,7 @@

  • Easily extensible to new processor architectures, SoC architecture, or board architectures. - A Porting Guide is available. + A Porting Guide is available.
  • @@ -536,7 +536,7 @@

    -

  • Power management sub-system.
  • +
  • Power management sub-system.
  • @@ -1009,7 +1009,7 @@ This configuration file contains a long list of settings that control what is built into NuttX and what is not. There are hundreds of such settings - (see the NuttX Porting Guide + (see the NuttX Porting Guide for a partial list that excludes platform specific settings). These many, many configuration options allow NuttX to be highly tuned to meet size requirements. @@ -3837,7 +3837,7 @@ pascal-3.0 2011-05-15 Gregory Nutt <gnutt@nuttx.org> - Porting Guide + Porting Guide diff --git a/nuttx/Documentation/NuttxPortingGuide.html b/nuttx/Documentation/NuttxPortingGuide.html index 0b67eddb74..fec7106b00 100644 --- a/nuttx/Documentation/NuttxPortingGuide.html +++ b/nuttx/Documentation/NuttxPortingGuide.html @@ -12,7 +12,7 @@

    NuttX RTOS Porting Guide

    -

    Last Updated: January 12, 2013

    +

    Last Updated: January 13, 2013

    @@ -4482,7 +4482,8 @@ build
  • CONFIG_SCHED_HAVE_PARENT: Remember the ID of the parent thread when a new child thread is created. - This support enables a few minor features (such as SIGCHLD) and slightly increases the size of the Task Control Block (TCB) of every task to hold the ID of the parent thread. + This support enables some additional features (such as SIGCHLD) and modifies the behavior of other interfaces. + For example, it makes waitpid() more standards complete by restricting the waited-for tasks to the children of the caller. Default: disabled.
  • @@ -4601,10 +4602,11 @@ build CONFIG_SCHED_LPWORKPERIOD: How often the lower priority worker thread checks for work in units of microseconds. Default: 50*1000 (50 MS).
  • - CONFIG_SCHED_LPWORKSTACKSIZE - The stack size allocated for the lower priority worker thread. Default: CONFIG_IDLETHREAD_STACKSIZE. + CONFIG_SCHED_LPWORKSTACKSIZE: The stack size allocated for the lower priority worker thread. Default: CONFIG_IDLETHREAD_STACKSIZE.
  • - CONFIG_SCHED_WAITPID: Enables the waitpid() API + CONFIG_SCHED_WAITPID: Enables the waitpid() interface in a default, non-standard mode (non-standard in the sense that the waited for PID need not be child of the caller). + If SCHED_HAVE_PARENT is also defined, then this setting will modify the behavior or waitpid() (making more spec compliant) and will enable the waitid() and waitp() interfaces as well.
  • CONFIG_SCHED_ATEXIT: Enables the atexit() API diff --git a/nuttx/Documentation/NuttxUserGuide.html b/nuttx/Documentation/NuttxUserGuide.html index c6eabd29a5..3cfb63f11e 100644 --- a/nuttx/Documentation/NuttxUserGuide.html +++ b/nuttx/Documentation/NuttxUserGuide.html @@ -13,7 +13,7 @@

    NuttX Operating System

    User's Manual

    by

    Gregory Nutt

    -

    Last Updated: January 11, 2013

    +

    Last Updated: January 13, 2013

    @@ -1776,8 +1776,10 @@ priority of the calling task is returned.

    Task synchronization interfaces

    2.3.1 sched_lock

    @@ -1886,10 +1888,12 @@ on this thread of execution. Description:

    - The following discussion is a general description of the waitpid() interface. - However, as of this writing, the implementation of waitpid() is fragmentary (but usable). - It simply supports waiting for any task to complete execution. - NuttX does not support any concept of parent/child processes or of process groups nor signals related to child processes (SIGCHLD). + The following discussion is a general description of the waitpid() interface. + However, as of this writing, the implementation of waitpid() is incomplete (but usable). + If CONFIG_SCHED_HAVE_PARENT is defined, waitpid() will be a little more compliant to specifications. + Without CONFIG_SCHED_HAVE_PARENT, waitpid() simply supports waiting for any task to complete execution. + With CONFIG_SCHED_HAVE_PARENT, waitpid() will use SIGCHLD and can, therefore, wait for any child of the parent to complete. + The implementation is incomplete in either case, however: NuttX does not support any concept of process groups. Nor does NuttX retain the status of exited tasks so if waitpid() is called after a task has exited, then no status will be available. The options argument is currently ignored.
    @@ -2038,7 +2042,158 @@ on this thread of execution. Comparable to the POSIX interface of the same name, but the implementation is incomplete (as detailed above).

    -

    2.3.5 atexit

    +

    2.3.5 waitid

  • +

    +Function Prototype: +

    +    #include <sys/wait.h>
    +    #ifdef CONFIG_SCHED_HAVE_PARENT
    +    int waitid(idtype_t idtype, id_t id, FAR siginfo_t *info, int options);
    +    #endif
    +
    +

    + Description: +

    +
    + The following discussion is a general description of the waitid() interface. + However, as of this writing, the implementation of waitid() is incomplete (but usable). + If CONFIG_SCHED_HAVE_PARENT is defined, waitid() will be a little more compliant to specifications. + waitpid() simply supports waiting a specific child task (P_PID or for any child task P_ALL to complete execution. + SIGCHLD is used. + The implementation is incomplete in either case, however: NuttX does not support any concept of process groups. + Nor does NuttX retain the status of exited tasks so if waitpid() is called after a task has exited, then no status will be available. + The options argument is currently ignored. +
    +

    + The waitid() function suspends the calling thread until one child of the process containing the calling thread changes state. + It records the current state of a child in the structure pointed to by info. + If a child process changed state prior to the call to waitid(), waitid() returns immediately. + If more than one thread is suspended in wait() or waitpid() waiting termination of the same process, exactly one thread will return the process status at the time of the target process termination +

    +

    + The idtype and id arguments are used to specify which children waitid() will wait for. +

    +

    +

      +
    • + If idtype is P_PID, waitid() will wait for the child with a process ID equal to (pid_t)id. +
    • +
    • + If idtype is P_PGID, waitid() will wait for any child with a process group ID equal to (pid_t)id. +
    • +
    • + If idtype is P_ALL, waitid() will wait for any children and id is ignored. +
    +

    + The options argument is used to specify which state changes waitid() will will wait for. + It is formed by OR-ing together one or more of the following flags: +

    +
      +
    • + WEXITED: + Wait for processes that have exited. +
    • +
    • + WSTOPPED: + Status will be returned for any child that has stopped upon receipt of a signal. +
    • +
    • + WCONTINUES: + Status will be returned for any child that was stopped and has been continued. +
    • +
    • + WNOHANG: + Return immediately if there are no children to wait for. +
    • +
    • + WNOWAIT: + Keep the process whose status is returned in info in a waitable state. + This will not affect the state of the process; + the process may be waited for again after this call completes. +
    • +
    + The info argument must point to a siginfo_t structure. + If waitid() returns because a child process was found that satisfied the conditions indicated by the arguments idtype and options, then the structure pointed to by info will be filled in by the system with the status of the process. + The si_signo member will always be equal to SIGCHLD. +

    +

    + Input Parameters: + See the description above. +

    +

    + Returned Value: + If waitid() returns due to the change of state of one of its children, 0 is returned. + Otherwise, -1 is returned and errno is set to indicate the error. +

    +

    + The waitid() function will fail if: +

    +
      +
    • + ECHILD: +
    • + The calling process has no existing unwaited-for child processes. +
    • + EINTR: +
    • + The waitid() function was interrupted by a signal. +
    • + EINVAL: + An invalid value was specified for options, or idtype and id specify an invalid set of processes. +
    • +
    +

    + Assumptions/Limitations: +

    + POSIX Compatibility: + Comparable to the POSIX interface of the same name, but the implementation is incomplete (as detailed in the description above). +

    + +

    2.3.6 wait

    +

    +Function Prototype: +

    +    #include <sys/wait.h>
    +    #ifdef CONFIG_SCHED_HAVE_PARENT
    +    pid_t wait(FAR int *stat_loc);
    +    #endif
    +
    +

    + Description: +

    +
    + The following discussion is a general description of the wait() interface. + However, as of this writing, the implementation of wait() is incomplete (but usable). + wait() is based on waitpaid(). + See the description of waitpaid() for further information. +
    +

    + The wait() function will suspend execution of the calling thread until status information for one of its terminated child processes 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 wait() 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 towait(), return will be immediate. +

    +

    + The waitpid() function will behave identically to wait(), if its pid argument is (pid_t)-1 and the options argument is 0. + Otherwise, its behavior will be modified by the values of the pid and options arguments. +

    +

    + Input Parameters: +

    +
      +
    • stat_loc. The location to return the exit status
    • +
    +

    + Returned Value: + See the values returned by waitpaid(). +

    +

    + Assumptions/Limitations: +

    + POSIX Compatibility: + Comparable to the POSIX interface of the same name, but the implementation is incomplete (as detailed in the description waitpaid()). +

    + +

    2.3.7 atexit

    Function Prototype: @@ -2077,7 +2232,7 @@ on this thread of execution.

  • atexit() functions are not inherited when a new task is created.
  • -

    2.3.6 on_exit

    +

    2.3.8 on_exit

    Function Prototype: @@ -9023,9 +9178,9 @@ notify a task when a message is available on a queue.

  • pipe
  • poll
  • poll.h
  • +
  • posix_spawn
  • -
  • posix_spawn
  • posix_spawn_file_actions_addclose
  • posix_spawn_file_actions_adddup2
  • posix_spawn_file_actions_addopen
  • @@ -9107,10 +9262,10 @@ notify a task when a message is available on a queue.
  • recv
  • recvfrom
  • rename
  • - -
  • rmdir
  • rewinddir
  • + +
  • ROM disk driver
  • ROMFS
  • sched_getparam
  • @@ -9183,6 +9338,8 @@ notify a task when a message is available on a queue.
  • vfprintf
  • vprintf
  • vsprintf
  • +
  • wait
  • +
  • waitid
  • waitpid
  • Watchdog Timer Interfaces
  • wd_cancel
  • diff --git a/nuttx/TODO b/nuttx/TODO index 92b7ab4f57..88324c06bc 100644 --- a/nuttx/TODO +++ b/nuttx/TODO @@ -6,7 +6,7 @@ standards, things that could be improved, and ideas for enhancements. nuttx/ - (11) Task/Scheduler (sched/) + (10) Task/Scheduler (sched/) (1) Memory Managment (mm/) (2) Signals (sched/, arch/) (2) pthreads (sched/) @@ -58,17 +58,6 @@ o Task/Scheduler (sched/) Status: Closed. No, this behavior will not be implemented. Priority: Medium, required for good emulation of process/pthread model. - Title: WAIT.H - Description: Implement sys/wait.h and functions. Consider implementing wait, - waitpid, waitid. At present, a parent has no information about - child tasks. - - Update: A simple but usable version of waitpid() has been included. - This version is not compliant with all specifications and can be - enabled with CONFIG_SCHED_WAITPID. - Status: Open, however no further work is planned. - Priority: Low - Title: MISSING ERRNO SETTINGS Description: Several APIs do not set errno. Need to review all APIs. Update: These are being fixed as they are encountered. There is diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt index 2724cf5a3c..4800f02eeb 100644 --- a/nuttx/configs/README.txt +++ b/nuttx/configs/README.txt @@ -335,10 +335,11 @@ defconfig -- This is a configuration file similar to the Linux task name to save in the TCB. Useful if scheduler instrumentation is selected. Set to zero to disable. CONFIG_SCHED_HAVE_PARENT - Remember the ID of the parent thread - when a new child thread is created. This support enables a - few minor features (such as SIGCHLD) and slightly increases - the size of the Task Control Block (TCB) of every task to hold - the ID of the parent thread. Default: disabled. + when a new child thread is created. This support enables some + additional features (such as SIGCHLD) and modifies the behavior + of other interfaces. For example, it makes waitpid() more + standards complete by restricting the waited-for tasks to the + children of the caller. Default: disabled. CONFIG_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY - Used to initialize the internal time logic. CONFIG_GREGORIAN_TIME - Enables Gregorian time conversions. @@ -417,7 +418,12 @@ defconfig -- This is a configuration file similar to the Linux checks for work in units of microseconds. Default: 50*1000 (50 MS). CONFIG_SCHED_LPWORKSTACKSIZE - The stack size allocated for the lower priority worker thread. Default: CONFIG_IDLETHREAD_STACKSIZE. - CONFIG_SCHED_WAITPID - Enables the waitpid() API + CONFIG_SCHED_WAITPID - Enables the waitpid() interface in a default, + non-standard mode (non-standard in the sense that the waited for + PID need not be child of the caller). If SCHED_HAVE_PARENT is + also defined, then this setting will modify the behavior or + waitpid() (making more spec compliant) and will enable the + waitid() and wait() interfaces as well. CONFIG_SCHED_ATEXIT - Enables the atexit() API CONFIG_SCHED_ATEXIT_MAX - By default if CONFIG_SCHED_ATEXIT is selected, only a single atexit() function is supported. That number diff --git a/nuttx/configs/sim/ostest/defconfig b/nuttx/configs/sim/ostest/defconfig index 5cea9a6d44..c8d5c501d7 100644 --- a/nuttx/configs/sim/ostest/defconfig +++ b/nuttx/configs/sim/ostest/defconfig @@ -143,7 +143,7 @@ CONFIG_MUTEX_TYPES=y # CONFIG_FDCLONE_STDIO is not set CONFIG_SDCLONE_DISABLE=y # CONFIG_SCHED_WORKQUEUE is not set -# CONFIG_SCHED_WAITPID is not set +CONFIG_SCHED_WAITPID=y # CONFIG_SCHED_ATEXIT is not set # CONFIG_SCHED_ONEXIT is not set CONFIG_USER_ENTRYPOINT="ostest_main" diff --git a/nuttx/include/nuttx/sched.h b/nuttx/include/nuttx/sched.h index 6c67e15005..b2ec1cee4d 100644 --- a/nuttx/include/nuttx/sched.h +++ b/nuttx/include/nuttx/sched.h @@ -1,7 +1,7 @@ /******************************************************************************** * include/nuttx/sched.h * - * Copyright (C) 2007-2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2007-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -204,6 +204,7 @@ struct _TCB pid_t pid; /* This is the ID of the thread */ #ifdef CONFIG_SCHED_HAVE_PARENT pid_t parent; /* This is the ID of the parent thread */ + uint16_t nchildren; /* This is the number active children */ #endif start_t start; /* Thread start function */ entry_t entry; /* Entry Point into the thread */ @@ -226,7 +227,7 @@ struct _TCB # endif #endif -#ifdef CONFIG_SCHED_WAITPID +#if defined(CONFIG_SCHED_WAITPID) && !defined(CONFIG_SCHED_HAVE_PARENT) sem_t exitsem; /* Support for waitpid */ int *stat_loc; /* Location to return exit status */ #endif diff --git a/nuttx/include/sys/types.h b/nuttx/include/sys/types.h index 2ae69d4a7e..95feee72ef 100644 --- a/nuttx/include/sys/types.h +++ b/nuttx/include/sys/types.h @@ -154,7 +154,9 @@ typedef uint16_t dev_t; typedef uint16_t ino_t; -/* pid_t is used for process IDs and process group IDs */ +/* pid_t is used for process IDs and process group IDs. It must be signed because + * negative PID values are used to represent invalid PIDs. + */ typedef int pid_t; diff --git a/nuttx/include/sys/wait.h b/nuttx/include/sys/wait.h index 6af1e971e4..2476adef96 100644 --- a/nuttx/include/sys/wait.h +++ b/nuttx/include/sys/wait.h @@ -1,7 +1,7 @@ /**************************************************************************** * include/sys/wait.h * - * Copyright (C) 2011 Gregory Nutt. All rights reserved. + * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -66,7 +66,7 @@ #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), + * argument to waitpid() (1) and/or waitid() (2), */ #define WCONTINUED (1 << 0) /* Status for child that has been continued (1)(2) */ @@ -104,9 +104,9 @@ extern "C" { #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); +EXTERN pid_t wait(FAR int *stat_loc); +EXTERN int waitid(idtype_t idtype, id_t id, FAR siginfo_t *info, int options); +EXTERN pid_t waitpid(pid_t pid, FAR int *stat_loc, int options); #undef EXTERN #if defined(__cplusplus) diff --git a/nuttx/sched/Kconfig b/nuttx/sched/Kconfig index 69621a1fa1..6d53a03aa7 100644 --- a/nuttx/sched/Kconfig +++ b/nuttx/sched/Kconfig @@ -43,9 +43,10 @@ config SCHED_HAVE_PARENT default n ---help--- Remember the ID of the parent thread when a new child thread is - created. This support enables a few minor features (such as - SIGCHLD) and slightly increases the size of the Task Control Block - (TCB) of every task to hold the ID of the parent thread. Default: + created. This support enables some additional features (such as + SIGCHLD) and modifies the behavior of other interfaces. For + example, it makes waitpid() more standards complete by restricting + the waited-for tasks to the children of the caller. Default: disabled. config JULIAN_TIME @@ -206,7 +207,12 @@ config SCHED_WAITPID bool "Enable waitpid() API" default n ---help--- - Enables the waitpid() API + Enables the waitpid() interface in a default, non-standard mode + (non-standard in the sense that the waited for PID need not be child + of the caller). If SCHED_HAVE_PARENT is also defined, then this + setting will modify the behavior or waitpid() (making more spec + compliant) and will enable the waitid() and wait() interfaces as + well. config SCHED_ATEXIT bool "Enable atexit() API" diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile index 23d1e9938e..3d6b58bacf 100644 --- a/nuttx/sched/Makefile +++ b/nuttx/sched/Makefile @@ -1,7 +1,7 @@ ############################################################################ # sched/Makefile # -# Copyright (C) 2007-2012 Gregory Nutt. All rights reserved. +# Copyright (C) 2007-2013 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -69,6 +69,9 @@ endif ifeq ($(CONFIG_SCHED_WAITPID),y) SCHED_SRCS += sched_waitpid.c +ifeq ($(CONFIG_SCHED_HAVE_PARENT),y) +SCHED_SRCS += sched_waitid.c sched_wait.c +endif endif ENV_SRCS = env_getenvironptr.c env_dup.c env_share.c env_release.c \ diff --git a/nuttx/sched/os_internal.h b/nuttx/sched/os_internal.h index 13b8083cff..32d9fb4ac3 100644 --- a/nuttx/sched/os_internal.h +++ b/nuttx/sched/os_internal.h @@ -83,10 +83,10 @@ enum os_crash_codes_e OSERR_BADREPRIORITIZESTATE /* Attempt to reprioritize in bad state or priority */ }; -/* Special task IDS */ +/* Special task IDS. Any negative PID is invalid. */ -#define NULL_TASK_PROCESS_ID 0 -#define INVALID_PROCESS_ID 0 +#define NULL_TASK_PROCESS_ID (pid_t)0 +#define INVALID_PROCESS_ID (pid_t)-1 /* Although task IDs can take the (positive, non-zero) * range of pid_t, the number of tasks that will be supported diff --git a/nuttx/sched/sched_wait.c b/nuttx/sched/sched_wait.c new file mode 100644 index 0000000000..813d4f8427 --- /dev/null +++ b/nuttx/sched/sched_wait.c @@ -0,0 +1,90 @@ +/***************************************************************************** + * sched/sched_wait.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 + +#include + +#include "os_internal.h" + +#if defined(CONFIG_SCHED_WAITPID) && defined(CONFIG_SCHED_HAVE_PARENT) + +/***************************************************************************** + * Private Functions + *****************************************************************************/ + +/***************************************************************************** + * Public Functions + *****************************************************************************/ + +/***************************************************************************** + * Name: wait + * + * Description: + * The wait() function will suspend execution of the calling thread until + * status information for one of its terminated child processes 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 wait() or 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 wait(), return will be immediate. + * + * The waitpid() function will behave identically to wait(), if the pid + * argument is (pid_t)-1 and the options argument is 0. Otherwise, its + * behaviour will be modified by the values of the pid and options arguments. + * + * Input Parameters: + * stat_loc - The location to return the exit status + * + * Returned Value: + * See waitpid(); + * + *****************************************************************************/ + +pid_t wait(FAR int *stat_loc) +{ + return waitpid((pid_t)-1, stat_loc, 0); +} + +#endif /* CONFIG_SCHED_WAITPID && CONFIG_SCHED_HAVE_PARENT*/ diff --git a/nuttx/sched/sched_waitid.c b/nuttx/sched/sched_waitid.c new file mode 100644 index 0000000000..eabc69afea --- /dev/null +++ b/nuttx/sched/sched_waitid.c @@ -0,0 +1,256 @@ +/***************************************************************************** + * sched/sched_waitid.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 + +#include + +#include "os_internal.h" + +#if defined(CONFIG_SCHED_WAITPID) && defined(CONFIG_SCHED_HAVE_PARENT) + +/***************************************************************************** + * Private Functions + *****************************************************************************/ + +/***************************************************************************** + * Public Functions + *****************************************************************************/ + +/***************************************************************************** + * Name: waitid + * + * Description: + * The waitid() function suspends the calling thread until one child of + * the process containing the calling thread changes state. It records the + * current state of a child in the structure pointed to by 'info'. If a + * child process changed state prior to the call to waitid(), waitid() + * returns immediately. If more than one thread is suspended in wait() or + * waitpid() waiting termination of the same process, exactly one thread + * will return the process status at the time of the target process + * termination + * + * The idtype and id arguments are used to specify which children waitid() + * will wait for. + * + * If idtype is P_PID, waitid() will wait for the child with a process + * ID equal to (pid_t)id. + * + * If idtype is P_PGID, waitid() will wait for any child with a process + * group ID equal to (pid_t)id. + * + * If idtype is P_ALL, waitid() will wait for any children and id is + * ignored. + * + * The options argument is used to specify which state changes waitid() + * will will wait for. It is formed by OR-ing together one or more of the + * following flags: + * + * WEXITED - Wait for processes that have exited. + * WSTOPPED - Status will be returned for any child that has stopped + * upon receipt of a signal. + * WCONTINUED - Status will be returned for any child that was stopped + * and has been continued. + * WNOHANG - Return immediately if there are no children to wait for. + * WNOWAIT - Keep the process whose status is returned in 'info' in a + * waitable state. This will not affect the state of the process; the + * process may be waited for again after this call completes. + * + * The 'info' argument must point to a siginfo_t structure. If waitid() + * returns because a child process was found that satisfied the conditions + * indicated by the arguments idtype and options, then the structure pointed + * to by 'info' will be filled in by the system with the status of the + * process. The si_signo member will always be equal to SIGCHLD. + * + * Input Parameters: + * See description. + * + * Returned Value: + * If waitid() returns due to the change of state of one of its children, + * 0 is returned. Otherwise, -1 is returned and errno is set to indicate + * the error. + * + * The waitid() function will fail if: + * + * ECHILD - The calling process has no existing unwaited-for child + * processes. + * EINTR - The waitid() function was interrupted by a signal. + * EINVAL - An invalid value was specified for options, or idtype and id + * specify an invalid set of processes. + * + *****************************************************************************/ + +int waitid(idtype_t idtype, id_t id, siginfo_t *info, int options) +{ + FAR _TCB *rtcb = (FAR _TCB *)g_readytorun.head; + sigset_t sigset; + int err; + int ret; + + /* MISSING LOGIC: If WNOHANG is provided in the options, then this function + * should returned immediately. However, there is no mechanism available now + * know if the thread has child: The children remember their parents (if + * CONFIG_SCHED_HAVE_PARENT) but the parents do not remember their children. + */ + + /* None of the options are supported except for WEXITED (which must be + * provided. Currently SIGCHILD always reports CLD_EXITED so we cannot + * distinguish any other events. + */ + +#ifdef CONFIG_DEBUG + if (options != WEXITED) + { + set_errno(ENOSYS); + return ERROR; + } +#endif + + /* Create a signal set that contains only SIGCHLD */ + + (void)sigemptyset(&sigset); + (void)sigaddset(&sigset, SIGCHLD); + + /* Disable pre-emption so that nothing changes while the loop executes */ + + sched_lock(); + + /* Verify that this task actually has children and that the the requeste + * TCB is actually a child of this task. + */ + + if (rtcb->nchildren == 0) + { + err = ECHILD; + goto errout_with_errno; + } + else if (idtype == P_PID) + { + /* Get the TCB corresponding to this PID and make sure it is our child. */ + + FAR _TCB *ctcb = sched_gettcb((pid_t)id); + if (!ctcb || ctcb->parent != rtcb->pid) + { + err = ECHILD; + goto errout_with_errno; + } + } + + /* Loop until the child that we are waiting for dies */ + + for (;;) + { + /* Check if the task has already died. Signals are not queued in + * NuttX. So a possibility is that the child has died and we + * missed the death of child signal (we got some other signal + * instead). + */ + + if (rtcb->nchildren == 0 || + (idtype == P_PID && (ret = kill((pid_t)id, 0)) < 0)) + { + /* We know that the child task was running okay we stared, + * so we must have lost the signal. What can we do? + * Let's claim we were interrupted by a signal. + */ + + err = EINTR; + goto errout_with_errno; + } + + /* Wait for any death-of-child signal */ + + ret = sigwaitinfo(&sigset, info); + if (ret < 0) + { + goto errout; + } + + /* Make there this was SIGCHLD */ + + if (info->si_signo == SIGCHLD) + { + /* Yes.. Are we waiting for the death of a specific child? */ + + if (idtype == P_PID) + { + /* Was this the death of the thread we were waiting for? */ + + if (info->si_pid == (pid_t)id) + { + /* Yes... return success */ + + break; + } + } + + /* Are we waiting for any child to change state? */ + + else if (idtype == P_ALL) + { + /* Return success */ + + break; + } + + /* Other ID types are not supported */ + + else /* if (idtype == P_PGID) */ + { + set_errno(ENOSYS); + goto errout; + } + } + } + + sched_unlock(); + return OK; + +errout_with_errno: + set_errno(err); +errout: + sched_unlock(); + return ERROR; +} + +#endif /* CONFIG_SCHED_WAITPID && CONFIG_SCHED_HAVE_PARENT*/ diff --git a/nuttx/sched/sched_waitpid.c b/nuttx/sched/sched_waitpid.c index 692ef64102..dc715b2e92 100644 --- a/nuttx/sched/sched_waitpid.c +++ b/nuttx/sched/sched_waitpid.c @@ -1,7 +1,7 @@ /***************************************************************************** * sched/sched_waitpid.c * - * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved. + * Copyright (C) 2011-2013 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -41,13 +41,14 @@ #include #include +#include #include #include #include "os_internal.h" -#ifdef CONFIG_SCHED_WAITPID /* Experimental */ +#ifdef CONFIG_SCHED_WAITPID /***************************************************************************** * Private Functions @@ -58,7 +59,7 @@ *****************************************************************************/ /***************************************************************************** - * Name: sched_waitpid + * Name: waitpid * * Description: * @@ -172,10 +173,16 @@ * *****************************************************************************/ -/***************************************************************************/ -/* NOTE: This is a partially functional, experimental version of waitpid() */ -/***************************************************************************/ +/*************************************************************************** + * NOTE: This is a partially functional, experimental version of waitpid() + * + * If there is no SIGCHLD signal supported (CONFIG_SCHED_HAVE_PARENT not + * defined), then waitpid() is still available, but does not obey the + * restriction that the pid be a child of the caller. + * + ***************************************************************************/ +#ifndef CONFIG_SCHED_HAVE_PARENT pid_t waitpid(pid_t pid, int *stat_loc, int options) { _TCB *tcb; @@ -183,26 +190,31 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options) int err; int ret; - /* Disable pre-emption so that nothing changes in the following tests */ - - sched_lock(); - tcb = sched_gettcb(pid); - if (!tcb) - { - err = ECHILD; - goto errout_with_errno; - } + DEBUGASSERT(stat_loc); /* None of the options are supported */ #ifdef CONFIG_DEBUG if (options != 0) { - err = ENOSYS; - goto errout_with_errno; + set_errno(ENOSYS); + return ERROR; } #endif + /* Disable pre-emption so that nothing changes in the following tests */ + + sched_lock(); + + /* Get the TCB corresponding to this PID */ + + tcb = sched_gettcb(pid); + if (!tcb) + { + err = ECHILD; + goto errout_with_errno; + } + /* "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 @@ -245,4 +257,152 @@ errout: return ERROR; } +/*************************************************************************** + * + * If CONFIG_SCHED_HAVE_PARENT is defined, then waitpid will use the SIGHCLD + * signal. It can also handle the pid == (pid_t)-1 arguement. This is + * slightly more spec-compliant. + * + * But then I have to be concerned about the fact that NuttX does not queue + * signals. This means that a flurry of signals can cause signals to be + * lost (or to have the data in the struct siginfo to be overwritten by + * the next signal). + * + ***************************************************************************/ + +#else +pid_t waitpid(pid_t pid, int *stat_loc, int options) +{ + FAR _TCB *rtcb = (FAR _TCB *)g_readytorun.head; + FAR struct siginfo info; + sigset_t sigset; + int err; + int ret; + + DEBUGASSERT(stat_loc); + + /* None of the options are supported */ + +#ifdef CONFIG_DEBUG + if (options != 0) + { + set_errno(ENOSYS); + return ERROR; + } +#endif + + /* Create a signal set that contains only SIGCHLD */ + + (void)sigemptyset(&sigset); + (void)sigaddset(&sigset, SIGCHLD); + + /* Disable pre-emption so that nothing changes while the loop executes */ + + sched_lock(); + + /* Verify that this task actually has children and that the the requeste + * TCB is actually a child of this task. + */ + + if (rtcb->nchildren == 0) + { + err = ECHILD; + goto errout_with_errno; + } + else if (pid != (pid_t)-1) + { + /* Get the TCB corresponding to this PID and make sure it is our child. */ + + FAR _TCB *ctcb = sched_gettcb(pid); + if (!ctcb || ctcb->parent != rtcb->pid) + { + err = ECHILD; + goto errout_with_errno; + } + } + + /* Loop until the child that we are waiting for dies */ + + for (;;) + { + /* Check if the task has already died. Signals are not queued in + * NuttX. So a possibility is that the child has died and we + * missed the death of child signal (we got some other signal + * instead). + */ + + if (pid == (pid_t)-1) + { + /* We are waiting for any child, check if there are still + * chilren. + */ + + if (rtcb->nchildren == 0) + { + /* There were one or more children when we started so they + * must have exit'ed. There are just no bread crumbs left + * behind to tell us the PID(s) of the existed children. + * Reporting ECHLD is about all we can do in this case. + */ + + err = ECHILD; + goto errout_with_errno; + } + } + else + { + /* We are waiting for a specific PID. We can use kill() with + * signal number 0 to determine if that task is still alive. + */ + + ret = kill(pid, 0); + if (ret < 0) + { + /* It is no longer running. We know that the child task was + * running okay when we started, so we must have lost the + * signal. In this case, we know that the task exit'ed, but + * we do not know its exit status. It would be better to + * reported ECHILD that bogus status. + */ + + err = ECHILD; + goto errout_with_errno; + } + } + + /* Wait for any death-of-child signal */ + + ret = sigwaitinfo(&sigset, &info); + if (ret < 0) + { + goto errout_with_lock; + } + + /* Was this the death of the thread we were waiting for? In the of + * pid == (pid_t)-1, we are waiting for any child thread. + */ + + if (info.si_signo == SIGCHLD && + (pid == (pid_t)-1 || info.si_pid == pid)) + { + /* Yes... return the status and PID (in the event it was -1) */ + + *stat_loc = info.si_status; + pid = info.si_pid; + break; + } + } + + sched_unlock(); + return (int)pid; + +errout_with_errno: + set_errno(err); + +errout_with_lock: + sched_unlock(); + return ERROR; +} +#endif /* CONFIG_SCHED_HAVE_PARENT */ + #endif /* CONFIG_SCHED_WAITPID */ diff --git a/nuttx/sched/task_exithook.c b/nuttx/sched/task_exithook.c index 9ce2e5899c..1106f28852 100644 --- a/nuttx/sched/task_exithook.c +++ b/nuttx/sched/task_exithook.c @@ -217,6 +217,20 @@ static inline void task_sigchild(FAR _TCB *tcb, int status) return; } + /* Decrement the number of children from this parent */ + + DEBUGASSERT(ptcb->nchildren > 0); + ptcb->nchildren--; + + /* Set the parent to an impossible PID. We do this because under certain + * conditions, task_exithook() can be called multiple times. If this + * function is called again, sched_gettcb() will fail on the invalid + * parent PID above, nchildren will be decremented once and all will be + * well. + */ + + tcb->parent = INVALID_PROCESS_ID; + /* Create the siginfo structure. We don't actually know the cause. That * is a bug. Let's just say that the child task just exit-ted for now. */ @@ -246,7 +260,7 @@ static inline void task_sigchild(FAR _TCB *tcb, int status) * ****************************************************************************/ -#ifdef CONFIG_SCHED_WAITPID +#if defined(CONFIG_SCHED_WAITPID) && !defined(CONFIG_SCHED_HAVE_PARENT) static inline void task_exitwakeup(FAR _TCB *tcb, int status) { /* Wakeup any tasks waiting for this task to exit */ @@ -310,14 +324,14 @@ void task_exithook(FAR _TCB *tcb, int status) task_atexit(tcb); - /* Send SIGCHLD to the parent of the exiting task */ - - task_sigchild(tcb, status); - /* Call any registered on_exit function(s) */ task_onexit(tcb, status); + /* Send SIGCHLD to the parent of the exit-ing task */ + + task_sigchild(tcb, status); + /* Wakeup any tasks waiting for this task to exit */ task_exitwakeup(tcb, status); diff --git a/nuttx/sched/task_setup.c b/nuttx/sched/task_setup.c index c5dd8ca3a8..92897f0ae6 100644 --- a/nuttx/sched/task_setup.c +++ b/nuttx/sched/task_setup.c @@ -168,7 +168,10 @@ static int task_assignpid(FAR _TCB *tcb) static inline void task_saveparent(FAR _TCB *tcb) { FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head; + + DEBUGASSERT(rtcb->nchildren < UINT16_MAX); tcb->parent = rtcb->pid; + rtcb->nchildren++; } #else # define task_saveparent(tcb)