aboutsummaryrefslogtreecommitdiff
path: root/nuttx/sched
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-01-13 18:53:00 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-01-13 18:53:00 +0000
commitb3f3dd123c181fe851f0a9756bed7acd4ba4ef7d (patch)
treedf530299e0171e8a86a2709ed4f19a1468efda4e /nuttx/sched
parentffda55b34a9a8a4a84f4cbc1da3836b944baec46 (diff)
downloadpx4-firmware-b3f3dd123c181fe851f0a9756bed7acd4ba4ef7d.tar.gz
px4-firmware-b3f3dd123c181fe851f0a9756bed7acd4ba4ef7d.tar.bz2
px4-firmware-b3f3dd123c181fe851f0a9756bed7acd4ba4ef7d.zip
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
Diffstat (limited to 'nuttx/sched')
-rw-r--r--nuttx/sched/Kconfig14
-rw-r--r--nuttx/sched/Makefile5
-rw-r--r--nuttx/sched/os_internal.h6
-rw-r--r--nuttx/sched/sched_wait.c90
-rw-r--r--nuttx/sched/sched_waitid.c256
-rw-r--r--nuttx/sched/sched_waitpid.c192
-rw-r--r--nuttx/sched/task_exithook.c24
-rw-r--r--nuttx/sched/task_setup.c3
8 files changed, 561 insertions, 29 deletions
diff --git a/nuttx/sched/Kconfig b/nuttx/sched/Kconfig
index 69621a1fa..6d53a03aa 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 23d1e9938..3d6b58bac 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 <gnutt@nuttx.org>
#
# 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 13b8083cf..32d9fb4ac 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 000000000..813d4f842
--- /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 <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Included Files
+ *****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/wait.h>
+#include <signal.h>
+#include <errno.h>
+
+#include <nuttx/sched.h>
+
+#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 000000000..eabc69afe
--- /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 <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Included Files
+ *****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/wait.h>
+#include <signal.h>
+#include <errno.h>
+
+#include <nuttx/sched.h>
+
+#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 692ef6410..dc715b2e9 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 <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -41,13 +41,14 @@
#include <sys/wait.h>
#include <semaphore.h>
+#include <signal.h>
#include <errno.h>
#include <nuttx/sched.h>
#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,9 +190,24 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options)
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
+
/* 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)
{
@@ -193,16 +215,6 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options)
goto errout_with_errno;
}
- /* None of the options are supported */
-
-#ifdef CONFIG_DEBUG
- 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
@@ -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 9ce2e5899..1106f2885 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 c5dd8ca3a..92897f0ae 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)