aboutsummaryrefslogtreecommitdiff
path: root/nuttx/sched
diff options
context:
space:
mode:
authorpx4dev <px4@purgatory.org>2013-01-17 01:00:46 -0800
committerpx4dev <px4@purgatory.org>2013-01-17 01:00:46 -0800
commit1a532d16dd3a90f20c3668b00ea4f3a86ea32c49 (patch)
treea770db1fe91e5a3c08e4cb03b216ac36c6f7684d /nuttx/sched
parent7d7c352fb44b718cb96096a624a19b5225e39f92 (diff)
parentcaeef71797019505fd450b1a0ae573ac5e490c6e (diff)
downloadpx4-firmware-1a532d16dd3a90f20c3668b00ea4f3a86ea32c49.tar.gz
px4-firmware-1a532d16dd3a90f20c3668b00ea4f3a86ea32c49.tar.bz2
px4-firmware-1a532d16dd3a90f20c3668b00ea4f3a86ea32c49.zip
Merge NuttX r5527
Diffstat (limited to 'nuttx/sched')
-rw-r--r--nuttx/sched/Kconfig77
-rw-r--r--nuttx/sched/Makefile7
-rw-r--r--nuttx/sched/clock_time2ticks.c42
-rw-r--r--nuttx/sched/mq_initialize.c4
-rw-r--r--nuttx/sched/os_bringup.c22
-rw-r--r--nuttx/sched/os_internal.h6
-rw-r--r--nuttx/sched/sched_addprioritized.c2
-rw-r--r--nuttx/sched/sched_addreadytorun.c8
-rw-r--r--nuttx/sched/sched_setuptaskfiles.c3
-rw-r--r--nuttx/sched/sched_unlock.c1
-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/sig_kill.c7
-rw-r--r--nuttx/sched/sig_mqnotempty.c7
-rw-r--r--nuttx/sched/sig_queue.c13
-rw-r--r--nuttx/sched/sig_timedwait.c29
-rw-r--r--nuttx/sched/task_create.c2
-rw-r--r--nuttx/sched/task_deletecurrent.c20
-rw-r--r--nuttx/sched/task_exithook.c71
-rw-r--r--nuttx/sched/task_setup.c43
-rw-r--r--nuttx/sched/task_vfork.c338
-rw-r--r--nuttx/sched/timer_settime.c4
23 files changed, 1167 insertions, 77 deletions
diff --git a/nuttx/sched/Kconfig b/nuttx/sched/Kconfig
index bfaec3b5d..6d53a03aa 100644
--- a/nuttx/sched/Kconfig
+++ b/nuttx/sched/Kconfig
@@ -38,6 +38,17 @@ config TASK_NAME_SIZE
Useful if scheduler instrumentation is selected. Set to zero to
disable.
+config SCHED_HAVE_PARENT
+ bool "Remember Parent"
+ default n
+ ---help---
+ Remember the ID of the parent thread 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 JULIAN_TIME
bool "Enables Julian time conversions"
default n
@@ -127,6 +138,7 @@ config SDCLONE_DISABLE
config SCHED_WORKQUEUE
bool "Enable worker thread"
default n
+ depends on !DISABLE_SIGNALS
---help---
Create a dedicated "worker" thread to handle delayed processing from interrupt
handlers. This feature is required for some drivers but, if there are no
@@ -158,14 +170,6 @@ config SCHED_WORKSTACKSIZE
---help---
The stack size allocated for the worker thread. Default: 2K.
-config SIG_SIGWORK
- int "Worker thread wakeup signal"
- default 4
- depends on SCHED_WORKQUEUE
- ---help---
- The signal number that will be used to wake-up the worker thread.
- Default: 4
-
config SCHED_LPWORK
bool "Enable a lower priority worker thread"
default n
@@ -203,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"
@@ -310,6 +319,56 @@ config DISABLE_POLL
depends on DISABLE_OS_API
default n
+if !DISABLE_SIGNALS
+comment "Signal Numbers"
+
+config SIG_SIGUSR1
+ int "SIGUSR1"
+ default 1
+ ---help---
+ Value of standard user signal 1 (SIGUSR1). Default: 1
+
+config SIG_SIGUSR2
+ int "SIGUSR2"
+ default 2
+ ---help---
+ Value of standard user signal 2 (SIGUSR2). Default: 2
+
+config SIG_SIGALARM
+ int "SIGALRM"
+ default 3
+ ---help---
+ Default the signal number used with POSIX timers (SIGALRM).
+ Default: 3
+
+config SIG_SIGCHLD
+ int "SIGCHLD"
+ default 4
+ depends on SCHED_HAVE_PARENT
+ ---help---
+ The SIGCHLD signal is sent to the parent of a child process when it
+ exits, is interrupted (stopped), or resumes after being interrupted.
+ Default: 4
+
+config SIG_SIGCONDTIMEDOUT
+ int "SIGCONDTIMEDOUT"
+ default 16
+ depends on !DISABLE_PTHREAD
+ ---help---
+ This non-standard signal number is used the implementation of
+ pthread_cond_timedwait(). Default 16.
+
+config SIG_SIGWORK
+ int "SIGWORK"
+ default 17
+ depends on SCHED_WORKQUEUE
+ ---help---
+ SIGWORK is a non-standard signal used to wake up the internal NuttX
+ worker thread. This setting specifies the signal number that will be
+ used for SIGWORK. Default: 17
+
+endif
+
comment "Sizes of configurable things (0 disables)"
config MAX_TASKS
diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile
index 82f74fc3c..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
@@ -45,7 +45,7 @@ MISC_SRCS = os_start.c os_bringup.c errno_getptr.c errno_get.c errno_set.c \
TSK_SRCS = prctl.c task_create.c task_init.c task_setup.c task_activate.c \
task_start.c task_delete.c task_deletecurrent.c task_exithook.c \
- task_restart.c exit.c getpid.c sched_addreadytorun.c \
+ task_restart.c task_vfork.c exit.c getpid.c sched_addreadytorun.c \
sched_removereadytorun.c sched_addprioritized.c sched_mergepending.c \
sched_addblocked.c sched_removeblocked.c sched_free.c sched_gettcb.c \
sched_verifytcb.c sched_releasetcb.c
@@ -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/clock_time2ticks.c b/nuttx/sched/clock_time2ticks.c
index 9265872bb..012f4e4f1 100644
--- a/nuttx/sched/clock_time2ticks.c
+++ b/nuttx/sched/clock_time2ticks.c
@@ -89,14 +89,48 @@
int clock_time2ticks(FAR const struct timespec *reltime, FAR int *ticks)
{
+#ifdef CONFIG_HAVE_LONG_LONG
+ int64_t relnsec;
+
+ /* Convert the relative time into nanoseconds. The range of the int64_t is
+ * sufficiently large that there is no real need for range checking.
+ */
+
+ relnsec = (int64_t)reltime->tv_sec * NSEC_PER_SEC +
+ (int64_t)reltime->tv_nsec;
+
+ /* Convert nanoseconds to clock ticks, rounding up to the smallest integer
+ * that is greater than or equal to the exact number of tick.
+ */
+
+ *ticks = (int)((relnsec + NSEC_PER_TICK - 1) / NSEC_PER_TICK);
+ return OK;
+#else
int32_t relusec;
- /* Convert the relative time into microseconds.*/
+ /* This function uses an int32_t to only the relative time in microseconds.
+ * that means that the maximum supported relative time is 2,147,487.647
+ * seconds
+ */
+
+#if 0 // overkill
+ DEBUGASSERT(reltime->tv_sec < 2147487 ||
+ reltime->tv_sec == 2147487 &&
+ reltime->tv_nsec <= 647 * NSEC_PER_MSEC);
+#endif
+
+ /* Convert the relative time into microseconds, rounding up to the smallest
+ * value that is greater than or equal to the exact number of microseconds.
+ */
- relusec = reltime->tv_sec * USEC_PER_SEC + reltime->tv_nsec / NSEC_PER_USEC;
+ relusec = reltime->tv_sec * USEC_PER_SEC +
+ (reltime->tv_nsec + NSEC_PER_USEC - 1) / NSEC_PER_USEC;
- /* Convert microseconds to clock ticks */
+ /* Convert microseconds to clock ticks, rounding up to the smallest integer
+ * that is greater than or equal to the exact number of tick.
+ */
- *ticks = (relusec + USEC_PER_TICK - 1) / USEC_PER_TICK;
+ *ticks = (int)((relusec + USEC_PER_TICK - 1) / USEC_PER_TICK);
return OK;
+#endif
}
diff --git a/nuttx/sched/mq_initialize.c b/nuttx/sched/mq_initialize.c
index 5b03a1120..dd7c7ed0f 100644
--- a/nuttx/sched/mq_initialize.c
+++ b/nuttx/sched/mq_initialize.c
@@ -217,11 +217,11 @@ void mq_initialize(void)
void mq_desblockalloc(void)
{
- struct mq_des_block_s *mqdesblock;
+ FAR struct mq_des_block_s *mqdesblock;
/* Allocate a block of message descriptors */
- mqdesblock = (struct mq_des_block_s *)kmalloc(sizeof(struct mq_des_block_s));
+ mqdesblock = (FAR struct mq_des_block_s *)kmalloc(sizeof(struct mq_des_block_s));
if (mqdesblock)
{
int i;
diff --git a/nuttx/sched/os_bringup.c b/nuttx/sched/os_bringup.c
index e0a236bbe..610d8515a 100644
--- a/nuttx/sched/os_bringup.c
+++ b/nuttx/sched/os_bringup.c
@@ -57,9 +57,6 @@
#ifdef CONFIG_SCHED_WORKQUEUE
# include "work_internal.h"
#endif
-#ifdef CONFIG_BUILTIN_APP_START
-# include "apps/apps.h"
-#endif
#ifdef CONFIG_NUTTX_KERNEL
# include "arch/board/user_map.h"
#endif
@@ -112,22 +109,15 @@
* function is to serve as the "bottom half" of device
* drivers.
*
- * And the main application entry point. This may be one of two different
+ * And the main application entry point:
* symbols:
*
- * - USER_ENTRYPOINT: This is the default entry point used for all of the
- * example code in apps/examples.
- * - CONFIG_BUILTIN_APP_START: The system can also be configured to start
- * custom applications at however CONFIG_BUILTIN_APP_START
- * is defined in the NuttX start-up file.
+ * - USER_ENTRYPOINT: This is the default user application entry point.
*
****************************************************************************/
int os_bringup(void)
{
-#ifdef CONFIG_BUILTIN_APP_START
- static const char *argv[3] = {NULL, "init", NULL};
-#endif
int init_taskid;
/* Setup up the initial environment for the idle task. At present, this
@@ -188,19 +178,11 @@ int os_bringup(void)
svdbg("Starting init thread\n");
-#ifdef CONFIG_BUILTIN_APP_START
- /* Start the built-in named application, passing an "init" argument, so that
- * application can distinguish different run-levels
- */
-
- init_taskid = exec_namedapp(CONFIG_BUILTIN_APP_START, argv);
-#else
/* Start the default application at CONFIG_USER_ENTRYPOINT() */
init_taskid = TASK_CREATE("init", SCHED_PRIORITY_DEFAULT,
CONFIG_USERMAIN_STACKSIZE,
(main_t)CONFIG_USER_ENTRYPOINT, (const char **)NULL);
-#endif
ASSERT(init_taskid != ERROR);
/* We an save a few bytes by discarding the IDLE thread's environment. */
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_addprioritized.c b/nuttx/sched/sched_addprioritized.c
index 8f19a4731..20178fb9c 100644
--- a/nuttx/sched/sched_addprioritized.c
+++ b/nuttx/sched/sched_addprioritized.c
@@ -114,7 +114,7 @@ bool sched_addprioritized(FAR _TCB *tcb, DSEG dq_queue_t *list)
(next && sched_priority <= next->sched_priority);
next = next->flink);
- /* Add the tcb to the spot found in the list. Check if the tcb
+ /* Add the tcb to the spot found in the list. Check if the tcb
* goes at the end of the list. NOTE: This could only happen if list
* is the g_pendingtasks list!
*/
diff --git a/nuttx/sched/sched_addreadytorun.c b/nuttx/sched/sched_addreadytorun.c
index f6117b6ff..1e1829343 100644
--- a/nuttx/sched/sched_addreadytorun.c
+++ b/nuttx/sched/sched_addreadytorun.c
@@ -84,8 +84,8 @@
* btcb - Points to the blocked TCB that is ready-to-run
*
* Return Value:
- * true if the currently active task (the head of the
- * g_readytorun list) has changed.
+ * true if the currently active task (the head of the g_readytorun list)
+ * has changed.
*
* Assumptions:
* - The caller has established a critical section before
@@ -104,7 +104,7 @@ bool sched_addreadytorun(FAR _TCB *btcb)
bool ret;
/* Check if pre-emption is disabled for the current running task and if
- * the new ready-to-run task would cause the current running task to be
+ * the new ready-to-run task would cause the current running task to be
* preempted.
*/
@@ -123,7 +123,7 @@ bool sched_addreadytorun(FAR _TCB *btcb)
else if (sched_addprioritized(btcb, (FAR dq_queue_t*)&g_readytorun))
{
- /* Information the instrumentation logic that we are switching tasks */
+ /* Inform the instrumentation logic that we are switching tasks */
sched_note_switch(rtcb, btcb);
diff --git a/nuttx/sched/sched_setuptaskfiles.c b/nuttx/sched/sched_setuptaskfiles.c
index fe0b14143..d01b8d4cd 100644
--- a/nuttx/sched/sched_setuptaskfiles.c
+++ b/nuttx/sched/sched_setuptaskfiles.c
@@ -200,7 +200,8 @@ static inline void sched_dupsockets(FAR _TCB *tcb)
* tcb - tcb of the new task.
*
* Return Value:
- * None
+ * Zero (OK) is returned on success; A negated errno value is returned on
+ * failure.
*
* Assumptions:
*
diff --git a/nuttx/sched/sched_unlock.c b/nuttx/sched/sched_unlock.c
index 9a52e8358..5eafcfc9e 100644
--- a/nuttx/sched/sched_unlock.c
+++ b/nuttx/sched/sched_unlock.c
@@ -126,5 +126,6 @@ int sched_unlock(void)
irqrestore(flags);
}
+
return OK;
}
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/sig_kill.c b/nuttx/sched/sig_kill.c
index 17921015f..b3d74d8a1 100644
--- a/nuttx/sched/sig_kill.c
+++ b/nuttx/sched/sig_kill.c
@@ -84,6 +84,9 @@
int kill(pid_t pid, int signo)
{
+#ifdef CONFIG_SCHED_HAVE_PARENT
+ FAR _TCB *rtcb = (FAR _TCB *)g_readytorun.head;
+#endif
FAR _TCB *stcb;
siginfo_t info;
int ret = ERROR;
@@ -124,6 +127,10 @@ int kill(pid_t pid, int signo)
info.si_signo = signo;
info.si_code = SI_USER;
info.si_value.sival_ptr = NULL;
+#ifdef CONFIG_SCHED_HAVE_PARENT
+ info.si_pid = rtcb->pid;
+ info.si_status = OK;
+#endif
/* Send the signal */
diff --git a/nuttx/sched/sig_mqnotempty.c b/nuttx/sched/sig_mqnotempty.c
index 9a1fd7243..f7ae6fd0d 100644
--- a/nuttx/sched/sig_mqnotempty.c
+++ b/nuttx/sched/sig_mqnotempty.c
@@ -88,6 +88,9 @@ int sig_mqnotempty (int pid, int signo, union sigval value)
int sig_mqnotempty (int pid, int signo, void *sival_ptr)
#endif
{
+#ifdef CONFIG_SCHED_HAVE_PARENT
+ FAR _TCB *rtcb = (FAR _TCB *)g_readytorun.head;
+#endif
FAR _TCB *stcb;
siginfo_t info;
int ret = ERROR;
@@ -113,6 +116,10 @@ int sig_mqnotempty (int pid, int signo, void *sival_ptr)
#else
info.si_value.sival_ptr = sival_ptr;
#endif
+#ifdef CONFIG_SCHED_HAVE_PARENT
+ info.si_pid = rtcb->pid;
+ info.si_status = OK;
+#endif
/* Verify that we can perform the signalling operation */
diff --git a/nuttx/sched/sig_queue.c b/nuttx/sched/sig_queue.c
index dee1c798a..db404238e 100644
--- a/nuttx/sched/sig_queue.c
+++ b/nuttx/sched/sig_queue.c
@@ -111,6 +111,9 @@ int sigqueue (int pid, int signo, union sigval value)
int sigqueue(int pid, int signo, void *sival_ptr)
#endif
{
+#ifdef CONFIG_SCHED_HAVE_PARENT
+ FAR _TCB *rtcb = (FAR _TCB *)g_readytorun.head;
+#endif
FAR _TCB *stcb;
siginfo_t info;
int ret = ERROR;
@@ -142,13 +145,17 @@ int sigqueue(int pid, int signo, void *sival_ptr)
/* Create the siginfo structure */
- info.si_signo = signo;
- info.si_code = SI_QUEUE;
+ info.si_signo = signo;
+ info.si_code = SI_QUEUE;
#ifdef CONFIG_CAN_PASS_STRUCTS
- info.si_value = value;
+ info.si_value = value;
#else
info.si_value.sival_ptr = sival_ptr;
#endif
+#ifdef CONFIG_SCHED_HAVE_PARENT
+ info.si_pid = rtcb->pid;
+ info.si_status = OK;
+#endif
/* Send the signal */
diff --git a/nuttx/sched/sig_timedwait.c b/nuttx/sched/sig_timedwait.c
index 1b8dfd162..f8c619b21 100644
--- a/nuttx/sched/sig_timedwait.c
+++ b/nuttx/sched/sig_timedwait.c
@@ -38,6 +38,7 @@
****************************************************************************/
#include <nuttx/config.h>
+#include <nuttx/compiler.h>
#include <stdint.h>
#include <string.h>
@@ -119,6 +120,10 @@ static void sig_timeout(int argc, uint32_t itcb)
u.wtcb->sigunbinfo.si_signo = SIG_WAIT_TIMEOUT;
u.wtcb->sigunbinfo.si_code = SI_TIMER;
u.wtcb->sigunbinfo.si_value.sival_int = 0;
+#ifdef CONFIG_SCHED_HAVE_PARENT
+ u.wtcb->sigunbinfo.si_pid = 0; /* Not applicable */
+ u.wtcb->sigunbinfo.si_status = OK;
+#endif
up_unblock_task(u.wtcb);
}
}
@@ -223,7 +228,7 @@ int sigtimedwait(FAR const sigset_t *set, FAR struct siginfo *info,
/* The return value is the number of the signal that awakened us */
- ret = info->si_signo;
+ ret = sigpend->info.si_signo;
}
/* We will have to wait for a signal to be posted to this task. */
@@ -238,10 +243,25 @@ int sigtimedwait(FAR const sigset_t *set, FAR struct siginfo *info,
if (timeout)
{
- /* Convert the timespec to milliseconds */
+ /* Convert the timespec to system clock ticks, making sure that
+ * the resultint delay is greater than or equal to the requested
+ * time in nanoseconds.
+ */
- waitticks = MSEC2TICK(timeout->tv_sec * MSEC_PER_SEC
- + timeout->tv_nsec / NSEC_PER_MSEC);
+#ifdef CONFIG_HAVE_LONG_LONG
+ uint64_t waitticks64 = ((uint64_t)timeout->tv_sec * NSEC_PER_SEC +
+ (uint64_t)timeout->tv_nsec + NSEC_PER_TICK - 1) /
+ NSEC_PER_TICK;
+ DEBUGASSERT(waitticks64 <= UINT32_MAX);
+ waitticks = (uint32_t)waitticks64;
+#else
+ uint32_t waitmsec;
+
+ DEBUGASSERT(timeout->tv_sec < UINT32_MAX / MSEC_PER_SEC);
+ waitmsec = timeout->tv_sec * MSEC_PER_SEC +
+ (timeout->tv_nsec + NSEC_PER_MSEC - 1) / NSEC_PER_MSEC;
+ waitticks = (waitmsec + MSEC_PER_TICK - 1) / MSEC_PER_TICK;
+#endif
/* Create a watchdog */
@@ -326,6 +346,7 @@ int sigtimedwait(FAR const sigset_t *set, FAR struct siginfo *info,
{
memcpy(info, &rtcb->sigunbinfo, sizeof(struct siginfo));
}
+
irqrestore(saved_state);
}
diff --git a/nuttx/sched/task_create.c b/nuttx/sched/task_create.c
index 4d92c9bb0..801706cbf 100644
--- a/nuttx/sched/task_create.c
+++ b/nuttx/sched/task_create.c
@@ -169,6 +169,8 @@ static int thread_create(const char *name, uint8_t type, int priority,
ret = task_activate(tcb);
if (ret != OK)
{
+ /* The TCB was added to the active task list by task_schedsetup() */
+
dq_rem((FAR dq_entry_t*)tcb, (dq_queue_t*)&g_inactivetasks);
goto errout_with_tcb;
}
diff --git a/nuttx/sched/task_deletecurrent.c b/nuttx/sched/task_deletecurrent.c
index 77025f5e0..e1e06acf6 100644
--- a/nuttx/sched/task_deletecurrent.c
+++ b/nuttx/sched/task_deletecurrent.c
@@ -90,6 +90,9 @@
* Return Value:
* OK on success; or ERROR on failure
*
+ * Assumeptions:
+ * Interrupts are disabled.
+ *
****************************************************************************/
int task_deletecurrent(void)
@@ -108,13 +111,16 @@ int task_deletecurrent(void)
(void)sched_removereadytorun(dtcb);
rtcb = (FAR _TCB*)g_readytorun.head;
- /* We are not in a bad state -- the head of the ready to run task list
+ /* We are now in a bad state -- the head of the ready to run task list
* does not correspond to the thread that is running. Disabling pre-
* emption on this TCB and marking the new ready-to-run task as not
* running (see, for example, get_errno_ptr()).
+ *
+ * We disable pre-emption here by directly incrementing the lockcount
+ * (vs. calling sched_lock()).
*/
- sched_lock();
+ rtcb->lockcount++;
rtcb->task_state = TSTATE_TASK_READYTORUN;
/* Move the TCB to the specified blocked task list and delete it */
@@ -132,9 +138,15 @@ int task_deletecurrent(void)
(void)sched_mergepending();
}
- /* Now calling sched_unlock() should have no effect */
+ /* We can't use sched_unlock() to decrement the lock count because the
+ * sched_mergepending() call above might have changed the task at the
+ * head of the ready-to-run list. Furthermore, we should not need to
+ * perform the unlock action anyway because we know that the pending
+ * task list is empty. So all we really need to do is to decrement
+ * the lockcount on rctb.
+ */
- sched_unlock();
+ rtcb->lockcount--;
return OK;
}
diff --git a/nuttx/sched/task_exithook.c b/nuttx/sched/task_exithook.c
index 3bde8fb7a..1106f2885 100644
--- a/nuttx/sched/task_exithook.c
+++ b/nuttx/sched/task_exithook.c
@@ -41,6 +41,7 @@
#include <stdlib.h>
#include <unistd.h>
+#include <signal.h>
#include <debug.h>
#include <errno.h>
@@ -188,6 +189,70 @@ static inline void task_onexit(FAR _TCB *tcb, int status)
#endif
/****************************************************************************
+ * Name: task_sigchild
+ *
+ * Description:
+ * Send the SIGCHILD signal to the parent thread
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_SCHED_HAVE_PARENT
+static inline void task_sigchild(FAR _TCB *tcb, int status)
+{
+ FAR _TCB *ptcb;
+ siginfo_t info;
+
+ /* Keep things stationary through the following */
+
+ sched_lock();
+
+ /* Get the TCB of the receiving task */
+
+ ptcb = sched_gettcb(tcb->parent);
+ if (!ptcb)
+ {
+ /* The parent no longer exists... bail */
+
+ sched_unlock();
+ 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.
+ */
+
+ info.si_signo = SIGCHLD;
+ info.si_code = CLD_EXITED;
+ info.si_value.sival_ptr = NULL;
+ info.si_pid = tcb->pid;
+ info.si_status = status;
+
+ /* Send the signal. We need to use this internal interface so that we can
+ * provide the correct si_code value with the signal.
+ */
+
+ (void)sig_received(ptcb, &info);
+ sched_unlock();
+}
+#else
+# define task_sigchild(tcb,status)
+#endif
+
+/****************************************************************************
* Name: task_exitwakeup
*
* Description:
@@ -195,7 +260,7 @@ static inline void task_onexit(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 */
@@ -263,6 +328,10 @@ void task_exithook(FAR _TCB *tcb, int status)
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 a37fb165a..92897f0ae 100644
--- a/nuttx/sched/task_setup.c
+++ b/nuttx/sched/task_setup.c
@@ -147,6 +147,37 @@ static int task_assignpid(FAR _TCB *tcb)
}
/****************************************************************************
+ * Name: task_saveparent
+ *
+ * Description:
+ * Save the task ID of the parent task in the child task's TCB.
+ *
+ * Parameters:
+ * tcb - The TCB of the new, child task.
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * The parent of the new task is the task at the head of the ready-to-run
+ * list.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_SCHED_HAVE_PARENT
+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)
+#endif
+
+/****************************************************************************
* Name: task_dupdspace
*
* Description:
@@ -161,6 +192,8 @@ static int task_assignpid(FAR _TCB *tcb)
* None
*
* Assumptions:
+ * The parent of the new task is the task at the head of the ready-to-run
+ * list.
*
****************************************************************************/
@@ -231,8 +264,12 @@ int task_schedsetup(FAR _TCB *tcb, int priority, start_t start, main_t main)
tcb->start = start;
tcb->entry.main = main;
- /* exec() and pthread_create() inherit the signal mask of the
- * parent thread. I suppose that task_create() should as well.
+ /* Save the task ID of the parent task in the TCB */
+
+ task_saveparent(tcb);
+
+ /* exec(), pthread_create(), task_create(), and vfork() all
+ * inherit the signal mask of the parent thread.
*/
#ifndef CONFIG_DISABLE_SIGNALS
@@ -243,7 +280,7 @@ int task_schedsetup(FAR _TCB *tcb, int priority, start_t start, main_t main)
* until it is activated.
*/
- tcb->task_state = TSTATE_TASK_INVALID;
+ tcb->task_state = TSTATE_TASK_INVALID;
/* Clone the parent tasks D-Space (if it was running PIC). This
* must be done before calling up_initial_state() so that the
diff --git a/nuttx/sched/task_vfork.c b/nuttx/sched/task_vfork.c
new file mode 100644
index 000000000..46b2d8e9f
--- /dev/null
+++ b/nuttx/sched/task_vfork.c
@@ -0,0 +1,338 @@
+/****************************************************************************
+ * sched/task_vfork
+ *
+ * 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 <stdint.h>
+#include <assert.h>
+#include <queue.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/sched.h>
+
+#include "os_internal.h"
+#include "env_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: task_vforksetup
+ *
+ * Description:
+ * The vfork() function has the same effect as fork(), except that the
+ * behavior is undefined if the process created by vfork() either modifies
+ * any data other than a variable of type pid_t used to store the return
+ * value from vfork(), or returns from the function in which vfork() was
+ * called, or calls any other function before successfully calling _exit()
+ * or one of the exec family of functions.
+ *
+ * This functin provides one step in the overall vfork() sequence: It
+ * Allocates and initializes the child task's TCB. The overall sequence is:
+ *
+ * 1) User code calls vfork(). vfork() is provided in architecture-specific
+ * code.
+ * 2) vfork()and calls task_vforksetup().
+ * 3) task_vforksetup() allocates and configures the child task's TCB. This
+ * consists of:
+ * - Allocation of the child task's TCB.
+ * - Initialization of file descriptors and streams
+ * - Configuration of environment variables
+ * - Setup the intput parameters for the task.
+ * - Initialization of the TCB (including call to up_initial_state()
+ * 4) up_vfork() provides any additional operating context. up_vfork must:
+ * - Allocate and initialize the stack
+ * - Initialize special values in any CPU registers that were not
+ * already configured by up_initial_state()
+ * 5) up_vfork() then calls task_vforkstart()
+ * 6) task_vforkstart() then executes the child thread.
+ *
+ * Input Paremeters:
+ * retaddr - The return address from vfork() where the child task
+ * will be started.
+ *
+ * Returned Value:
+ * Upon successful completion, task_vforksetup() returns a pointer to
+ * newly allocated and initalized child task's TCB. NULL is returned
+ * on any failure and the errno is set appropriately.
+ *
+ ****************************************************************************/
+
+FAR _TCB *task_vforksetup(start_t retaddr)
+{
+ _TCB *parent = (FAR _TCB *)g_readytorun.head;
+ _TCB *child;
+ int priority;
+ int ret;
+
+ DEBUGASSERT(retaddr);
+
+ /* Allocate a TCB for the child task. */
+
+ child = (FAR _TCB*)kzalloc(sizeof(_TCB));
+ if (!child)
+ {
+ set_errno(ENOMEM);
+ return NULL;
+ }
+
+ /* Associate file descriptors with the new task */
+
+#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
+ ret = sched_setuptaskfiles(child);
+ if (ret != OK)
+ {
+ goto errout_with_tcb;
+ }
+#endif
+
+ /* Clone the parent's task environment */
+
+ (void)env_dup(child);
+
+ /* Mark the type of this thread (this setting will be needed in
+ * task_schedsetup() when up_initial_state() is called.
+ */
+
+ child->flags |= TCB_FLAG_TTYPE_TASK;
+
+ /* Get the priority of the parent task */
+
+#ifdef CONFIG_PRIORITY_INHERITANCE
+ priority = parent->base_priority; /* "Normal," unboosted priority */
+#else
+ priority = parent->sched_priority; /* Current priority */
+#endif
+
+ /* Initialize the task control block. This calls up_initial_state() */
+
+ svdbg("Child priority=%d start=%p\n", priority, retaddr);
+ ret = task_schedsetup(child, priority, retaddr, parent->entry.main);
+ if (ret != OK)
+ {
+ goto errout_with_tcb;
+ }
+
+ svdbg("parent=%p, returning child=%p\n", parent, child);
+ return child;
+
+errout_with_tcb:
+ sched_releasetcb(child);
+ set_errno(-ret);
+ return NULL;
+}
+
+/****************************************************************************
+ * Name: task_vforkstart
+ *
+ * Description:
+ * The vfork() function has the same effect as fork(), except that the
+ * behavior is undefined if the process created by vfork() either modifies
+ * any data other than a variable of type pid_t used to store the return
+ * value from vfork(), or returns from the function in which vfork() was
+ * called, or calls any other function before successfully calling _exit()
+ * or one of the exec family of functions.
+ *
+ * This functin provides one step in the overall vfork() sequence: It
+ * starts execution of the previously initialized TCB. The overall
+ * sequence is:
+ *
+ * 1) User code calls vfork()
+ * 2) Architecture-specific code provides vfork()and calls task_vforksetup().
+ * 3) task_vforksetup() allocates and configures the child task's TCB. This
+ * consists of:
+ * - Allocation of the child task's TCB.
+ * - Initialization of file descriptors and streams
+ * - Configuration of environment variables
+ * - Setup the intput parameters for the task.
+ * - Initialization of the TCB (including call to up_initial_state()
+ * 4) vfork() provides any additional operating context. vfork must:
+ * - Allocate and initialize the stack
+ * - Initialize special values in any CPU registers that were not
+ * already configured by up_initial_state()
+ * 5) vfork() then calls task_vforkstart()
+ * 6) task_vforkstart() then executes the child thread.
+ *
+ * Input Paremeters:
+ * retaddr - The return address from vfork() where the child task
+ * will be started.
+ *
+ * Returned Value:
+ * Upon successful completion, vfork() returns 0 to the child process and
+ * returns the process ID of the child process to the parent process.
+ * Otherwise, -1 is returned to the parent, no child process is created,
+ * and errno is set to indicate the error.
+ *
+ ****************************************************************************/
+
+pid_t task_vforkstart(FAR _TCB *child)
+{
+#if CONFIG_TASK_NAME_SIZE > 0
+ _TCB *parent = (FAR _TCB *)g_readytorun.head;
+#endif
+ FAR const char *name;
+ pid_t pid;
+#ifdef CONFIG_SCHED_WAITPID
+ int rc;
+#endif
+ int ret;
+
+ svdbg("Starting Child TCB=%p, parent=%p\n", child, g_readytorun.head);
+ DEBUGASSERT(child);
+
+ /* Setup to pass parameters to the new task */
+
+#if CONFIG_TASK_NAME_SIZE > 0
+ name = parent->name;
+#else
+ name = NULL;
+#endif
+
+ (void)task_argsetup(child, name, (const char **)NULL);
+
+ /* Get the assigned pid before we start the task */
+
+ pid = (int)child->pid;
+
+ /* Activate the task */
+
+ ret = task_activate(child);
+ if (ret != OK)
+ {
+ task_vforkabort(child, -ret);
+ return ERROR;
+ }
+
+ /* Since the child task has the same priority as the parent task, it is
+ * now ready to run, but has not yet ran. It is a requirement that
+ * the parent enivornment be stable while vfork runs; the child thread
+ * is still dependent on things in the parent thread... like the pointers
+ * into parent thread's stack which will still appear in the child's
+ * registers and environment.
+ *
+ * We do not have SIG_CHILD, so we have to do some silly things here.
+ * The simplest way to make sure that the child thread runs to completion
+ * is simply to yield here. Since the child can only do exit() or
+ * execv/l(), that should be all that is needed.
+ *
+ * Hmmm.. this is probably not sufficient. What if we are running
+ * SCHED_RR? What if the child thread is suspeneded and rescheduled
+ * after the parent thread again?
+ */
+
+#ifdef CONFIG_SCHED_WAITPID
+
+ /* We can also exploit a bug in the execv() implementation: The PID
+ * of the task exec'ed by the child will not be the same as the PID of
+ * the child task. Therefore, waitpid() on the child task's PID will
+ * accomplish what we need to do.
+ */
+
+ rc = 0;
+
+#ifdef CONFIG_DEBUG
+ ret = waitpid(pid, &rc, 0);
+ if (ret < 0)
+ {
+ sdbg("ERROR: waitpid failed: %d\n", errno);
+ }
+#else
+ (void)waitpid(pid, &rc, 0);
+#endif
+
+#else
+ /* The following logic does not appear to work... It gets stuff in an
+ * infinite kill() loop and hogs the processor. Therefore, it looks
+ * as though CONFIG_SCHED_WAITPID may be a requirement to used vfork().
+ *
+ * Again exploiting that execv() bug: Check if the child thread is
+ * still running.
+ */
+
+ while (kill(pid, 0) == OK)
+ {
+ /* Yes.. then we can yield to it -- assuming that it has not lowered
+ * its priority. sleep(0) might be a safer thing to do since it does
+ * not depend on prioirities: It will halt the parent thread for one
+ * system clock tick. This will delay the return to the parent thread.
+ */
+
+#ifndef CONFIG_DISABLE_SIGNALS
+ sleep(0);
+#else
+ sched_yield();
+#endif
+ }
+#endif
+
+ return pid;
+}
+
+/****************************************************************************
+ * Name: task_vforkabort
+ *
+ * Description:
+ * Recover from any errors after task_vforksetup() was called.
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void task_vforkabort(FAR _TCB *child, int errcode)
+{
+ /* The TCB was added to the active task list by task_schedsetup() */
+
+ dq_rem((FAR dq_entry_t*)child, (dq_queue_t*)&g_inactivetasks);
+
+ /* Release the TCB */
+
+ sched_releasetcb(child);
+ set_errno(errcode);
+}
diff --git a/nuttx/sched/timer_settime.c b/nuttx/sched/timer_settime.c
index 1814ba898..f09842ad4 100644
--- a/nuttx/sched/timer_settime.c
+++ b/nuttx/sched/timer_settime.c
@@ -113,6 +113,10 @@ static void inline timer_sigqueue(FAR struct posix_timer_s *timer)
#else
info.si_value.sival_ptr = timer->pt_value.sival_ptr;
#endif
+#ifdef CONFIG_SCHED_HAVE_PARENT
+ info.si_pid = 0; /* Not applicable */
+ info.si_status = OK;
+#endif
/* Send the signal */