aboutsummaryrefslogtreecommitdiff
path: root/nuttx/sched
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-01-07 19:35:47 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-01-07 19:35:47 +0000
commita5f001189e1a056be275e1d736e38893f96cd395 (patch)
treefca977319643c4fcdbaeecbd38ee572fb9c31ae1 /nuttx/sched
parent876062fe3a2b6273855b77c0ed1c9d0cbcfc43c6 (diff)
downloadpx4-firmware-a5f001189e1a056be275e1d736e38893f96cd395.tar.gz
px4-firmware-a5f001189e1a056be275e1d736e38893f96cd395.tar.bz2
px4-firmware-a5f001189e1a056be275e1d736e38893f96cd395.zip
This initial vfork() check-in was a little pollyanna-ish
git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5487 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/sched')
-rw-r--r--nuttx/sched/Makefile2
-rw-r--r--nuttx/sched/sched_setuptaskfiles.c3
-rw-r--r--nuttx/sched/task_create.c2
-rw-r--r--nuttx/sched/task_vfork.c266
4 files changed, 271 insertions, 2 deletions
diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile
index 82f74fc3c..23d1e9938 100644
--- a/nuttx/sched/Makefile
+++ b/nuttx/sched/Makefile
@@ -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
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/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_vfork.c b/nuttx/sched/task_vfork.c
new file mode 100644
index 000000000..93fcb46da
--- /dev/null
+++ b/nuttx/sched/task_vfork.c
@@ -0,0 +1,266 @@
+/****************************************************************************
+ * 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 <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() */
+
+ ret = task_schedsetup(child, priority, retaddr, parent->entry.main);
+ if (ret != OK)
+ {
+ goto errout_with_tcb;
+ }
+
+ 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)
+{
+ FAR const char *name;
+ pid_t pid;
+ int ret;
+
+ DEBUGASSERT(child);
+
+ /* Setup to pass parameters to the new task */
+
+#if CONFIG_TASK_NAME_SIZE > 0
+ name = parent->name;
+#else
+ name = "<noname>";
+#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;
+ }
+
+ 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);
+} \ No newline at end of file