summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-01-25 19:15:05 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-01-25 19:15:05 +0000
commite1ff898b022bc77ede6ba57e8ecb46f0af306149 (patch)
treeeb49c2f705d2255cc6f05a7ee433aa87472c8a88
parentf2933cc4b65836a712f1ab996512999959a8c48a (diff)
downloadpx4-nuttx-e1ff898b022bc77ede6ba57e8ecb46f0af306149.tar.gz
px4-nuttx-e1ff898b022bc77ede6ba57e8ecb46f0af306149.tar.bz2
px4-nuttx-e1ff898b022bc77ede6ba57e8ecb46f0af306149.zip
Add logic to keep track of members of a task group
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5563 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/include/nuttx/sched.h24
-rw-r--r--nuttx/sched/group_create.c74
-rw-r--r--nuttx/sched/group_join.c103
-rw-r--r--nuttx/sched/group_leave.c68
-rw-r--r--nuttx/sched/os_internal.h10
-rw-r--r--nuttx/sched/os_start.c19
-rw-r--r--nuttx/sched/pthread_create.c24
-rw-r--r--nuttx/sched/task_create.c17
-rw-r--r--nuttx/sched/task_exithook.c2
-rw-r--r--nuttx/sched/task_init.c13
10 files changed, 298 insertions, 56 deletions
diff --git a/nuttx/include/nuttx/sched.h b/nuttx/include/nuttx/sched.h
index 4a3bae5e4..a29f8dfeb 100644
--- a/nuttx/include/nuttx/sched.h
+++ b/nuttx/include/nuttx/sched.h
@@ -60,10 +60,18 @@
/* Configuration ****************************************************************/
/* Task groups currently only supported for retention of child status */
+#undef HAVE_TASK_GROUP
+#undef HAVE_GROUP_MEMBERS
+
#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS)
-# define HAVE_TASK_GROUP 1
-#else
-# undef HAVE_TASK_GROUP
+# define HAVE_TASK_GROUP 1
+# define HAVE_GROUP_MEMBERS 1
+#endif
+
+/* In any event, we don't need group members if support for pthreads is disabled */
+
+#ifdef CONFIG_PTHREADS_DISABLE
+# undef HAVE_GROUP_MEMBERS
#endif
/* Task Management Definitins ***************************************************/
@@ -255,12 +263,18 @@ struct dspace_s
#ifdef HAVE_TASK_GROUP
struct task_group_s
{
- uint16_t tg_crefs; /* Count of threads sharing this data */
- uint8_t tg_flags; /* See GROUP_FLAG_* definitions */
+ uint8_t tg_flags; /* See GROUP_FLAG_* definitions */
+ uint8_t tg_nmembers; /* Number of members in the group */
+#ifdef HAVE_GROUP_MEMBERS
+ uint8_t tg_mxmembers; /* Number of members in allocation */
+ FAR pid_t *tg_members; /* Members of the group */
+#endif
/* Child exit status **********************************************************/
+#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS)
FAR struct child_status_s *tg_children; /* Head of a list of child status */
+#endif
/* Environment varibles *******************************************************/
/* Not yet (see type environ_t) */
diff --git a/nuttx/sched/group_create.c b/nuttx/sched/group_create.c
index d036b9084..4612ae8c5 100644
--- a/nuttx/sched/group_create.c
+++ b/nuttx/sched/group_create.c
@@ -1,5 +1,5 @@
/*****************************************************************************
- * sched/group_create.c
+ * sched/group_allocate.c
*
* Copyright (C) 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@@ -51,6 +51,9 @@
/*****************************************************************************
* Pre-processor Definitions
*****************************************************************************/
+/* Is this worth making a configuration option? */
+
+#define GROUP_INITIAL_MEMBERS 4
/*****************************************************************************
* Private Types
@@ -69,11 +72,16 @@
*****************************************************************************/
/*****************************************************************************
- * Name: group_create
+ * Name: group_allocate
*
* Description:
- * Create and initialize a new task group structure for the specified TCB.
- * This function is called as part of the task creation sequence.
+ * Create and a new task group structure for the specified TCB. This
+ * function is called as part of the task creation sequence. The structure
+ * allocated and zered, but otherwise uninitialized. The full creation
+ * of the group of a two step process: (1) First, this function allocates
+ * group structure early in the task creation sequence in order to provide a
+ * group container, then (2) group_initialize() is called to set up the
+ * group membership.
*
* Parameters:
* tcb - The tcb in need of the task group.
@@ -87,24 +95,66 @@
*
*****************************************************************************/
-int group_create(FAR _TCB *tcb)
+int group_allocate(FAR _TCB *tcb)
{
+ DEBUGASSERT(tcb && !tcb->group);
+
+ /* Allocate the group structure and assign it to the TCB */
+
+ tcb->group = (FAR struct task_group_s *)kzalloc(sizeof(struct task_group_s));
+ return tcb->group ? OK : -ENOMEM;
+}
+
+/*****************************************************************************
+ * Name: group_initialize
+ *
+ * Description:
+ * Add the task as the initial member of the group. The full creation of
+ * the group of a two step process: (1) First, this group structure is
+ * allocated by group_allocate() early in the task creation sequence, then
+ * (2) this function is called to set up the initial group membership.
+ *
+ * Parameters:
+ * tcb - The tcb in need of the task group.
+ *
+ * Return Value:
+ * 0 (OK) on success; a negated errno value on failure.
+ *
+ * Assumptions:
+ * Called during task creation in a safe context. No special precautions
+ * are required here.
+ *
+ *****************************************************************************/
+
+int group_initialize(FAR _TCB *tcb)
+{
+#ifdef HAVE_GROUP_MEMBERS
FAR struct task_group_s *group;
- DEBUGASSERT(tcb && !tcb->group);
+ DEBUGASSERT(tcb && tcb->group);
+ group = tcb->group;
- /* Allocate the group structure */
+ /* Allocate space to hold GROUP_INITIAL_MEMBERS members of the group */
- group = (FAR struct task_group_s *)kzalloc(sizeof(struct task_group_s));
- if (!group)
+ group->tg_members = (FAR pid_t *)kmalloc(GROUP_INITIAL_MEMBERS*sizeof(pid_t));
+ if (!group->tg_members)
{
+ free(group);
return -ENOMEM;
}
- /* Initialize the group structure and assign it to the tcb */
+ /* Assign the PID of this new task as a member of the group*/
+
+ group->tg_members[0] = tcb->pid;
+
+ /* Initialize the non-zero elements of group structure and assign it to
+ * the tcb.
+ */
+
+ group->tg_mxmembers = GROUP_INITIAL_MEMBERS; /* Number of members in allocation */
+#endif
- group->tg_crefs = 1;
- tcb->group = group;
+ group->tg_nmembers = 1; /* Number of members in the group */
return OK;
}
diff --git a/nuttx/sched/group_join.c b/nuttx/sched/group_join.c
index 987c1ba87..9dcea6599 100644
--- a/nuttx/sched/group_join.c
+++ b/nuttx/sched/group_join.c
@@ -41,8 +41,11 @@
#include <sched.h>
#include <assert.h>
+#include <errno.h>
#include <debug.h>
+#include <nuttx/kmalloc.h>
+
#include "os_internal.h"
#ifdef HAVE_TASK_GROUP
@@ -50,6 +53,9 @@
/*****************************************************************************
* Pre-processor Definitions
*****************************************************************************/
+/* Is this worth making a configuration option? */
+
+#define GROUP_REALLOC_MEMBERS 4
/*****************************************************************************
* Private Types
@@ -68,19 +74,21 @@
*****************************************************************************/
/*****************************************************************************
- * Name: group_join
+ * Name: group_bind
*
* Description:
- * Copy the group structure reference from one TCB to another, incrementing
- * the refrence count on the group. This function is called when a pthread
- * is produced within the task group so that the pthread can share the
- * resources of the task group.
+ * A thread joins the group when it is created. This is a two step process,
+ * first, the group must bound to the new threads TCB. group_bind() does
+ * this (at the return from group_join, things are a little unstable: The
+ * group has been bound, but tg_nmembers hs not yet been incremented).
+ * Then, after the new thread is initialized and has a PID assigned to it,
+ * group_join() is called, incrementing the tg_nmembers count on the group.
*
* Parameters:
* tcb - The TCB of the new "child" task that need to join the group.
*
* Return Value:
- * None
+ * 0 (OK) on success; a negated errno value on failure.
*
* Assumptions:
* - The parent task from which the group will be inherited is the task at
@@ -90,18 +98,91 @@
*
*****************************************************************************/
-void group_join(FAR _TCB *tcb)
+int group_bind(FAR _TCB *tcb)
{
FAR _TCB *ptcb = (FAR _TCB *)g_readytorun.head;
DEBUGASSERT(ptcb && tcb && ptcb->group && !tcb->group);
- /* Copy the group reference from the parent to the child, incrementing the
- * reference count.
- */
+ /* Copy the group reference from the parent to the child */
tcb->group = ptcb->group;
- ptcb->group->tg_crefs++;
+ return OK;
+}
+
+/*****************************************************************************
+ * Name: group_join
+ *
+ * Description:
+ * A thread joins the group when it is created. This is a two step process,
+ * first, the group must bound to the new threads TCB. group_bind() does
+ * this (at the return from group_join, things are a little unstable: The
+ * group has been bound, but tg_nmembers hs not yet been incremented).
+ * Then, after the new thread is initialized and has a PID assigned to it,
+ * group_join() is called, incrementing the tg_nmembers count on the group.
+ *
+ * Parameters:
+ * tcb - The TCB of the new "child" task that need to join the group.
+ *
+ * Return Value:
+ * 0 (OK) on success; a negated errno value on failure.
+ *
+ * Assumptions:
+ * - The parent task from which the group will be inherited is the task at
+ * the thead of the ready to run list.
+ * - Called during thread creation in a safe context. No special precautions
+ * are required here.
+ *
+ *****************************************************************************/
+
+int group_join(FAR _TCB *tcb)
+{
+#ifdef HAVE_GROUP_MEMBERS
+ FAR struct task_group_s *group;
+
+ DEBUGASSERT(tcb && tcb->group &&
+ tcb->group->tg_nmembers < UINT8_MAX);
+
+ /* Get the group from the TCB */
+
+ group = tcb->group;
+
+ /* Will we need to extend the size of the array of groups? */
+
+ if (group->tg_nmembers >= group->tg_mxmembers)
+ {
+ FAR pid_t *newmembers;
+ unsigned int newmax;
+
+ /* Yes... reallocate the array of members */
+
+ newmax = group->tg_mxmembers + GROUP_REALLOC_MEMBERS;
+ if (newmax > UINT8_MAX)
+ {
+ newmax = UINT8_MAX;
+ }
+
+ newmembers = (FAR pid_t *)
+ krealloc(group->tg_members, sizeof(pid_t) * newmax);
+
+ if (!newmembers)
+ {
+ return -ENOMEM;
+ }
+
+ /* Save the new number of members in the reallocated members array */
+
+ group->tg_members = newmembers;
+ group->tg_mxmembers = newmax;
+ }
+
+ /* Assign this new pid to the group. */
+
+ group->tg_members[group->tg_nmembers] = tcb->pid;
+#endif
+
+ group->tg_nmembers++;
+ return OK;
}
#endif /* HAVE_TASK_GROUP */
diff --git a/nuttx/sched/group_leave.c b/nuttx/sched/group_leave.c
index 69a6ea8b2..223af1556 100644
--- a/nuttx/sched/group_leave.c
+++ b/nuttx/sched/group_leave.c
@@ -92,6 +92,7 @@
void group_leave(FAR _TCB *tcb)
{
FAR struct task_group_s *group;
+ int i;
DEBUGASSERT(tcb);
@@ -100,17 +101,69 @@ void group_leave(FAR _TCB *tcb)
group = tcb->group;
if (group)
{
- /* Would the reference count decrement to zero? */
+#ifdef HAVE_GROUP_MEMBERS
+ /* Find the member in the array of members and remove it */
- if (group->tg_crefs > 1)
+ for (i = 0; i < group->tg_nmembers; i++)
{
- /* No.. just decrement the reference count and return */
+ /* Does this member have the matching pid */
+
+ if (group->tg_members[i] == tcb->pid)
+ {
+ /* Yes.. break out of the loop. We don't do the actual
+ * removal here, instead we re-test i and do the adjustments
+ * outside of the loop. We do this because we want the
+ * DEBUGASSERT to work properly.
+ */
+
+ break;
+ }
+ }
+
+ /* Now, test if we found the task in the array of members. */
+
+ DEBUGASSERT(i < group->tg_nmembers);
+ if (i < group->tg_nmembers)
+ {
+ /* Yes..Is this the last member of the group? */
+
+ if (group->tg_nmembers > 1)
+ {
+ /* No.. remove the member from the array of members */
+
+ group->tg_members[i] = group->tg_members[group->tg_nmembers - 1];
+ group->tg_nmembers--;
+ }
+
+ /* Yes.. that was the last member remaining in the group */
+
+ else
+ {
+ /* Release all of the resource contained within the group */
+ /* Free all un-reaped child exit status */
+
+ task_removechildren(tcb);
- group->tg_crefs--;
+ /* Release the group container itself */
+
+ sched_free(group);
+ }
+ }
+#else
+ /* Yes..Is this the last member of the group? */
+
+ if (group->tg_nmembers > 1)
+ {
+ /* No.. just decrement the number of members in the group */
+
+ group->tg_nmembers--;
}
+
+ /* Yes.. that was the last member remaining in the group */
+
else
{
- /* Yes.. Release all of the resource contained within the group */
+ /* Release all of the resource contained within the group */
/* Free all un-reaped child exit status */
task_removechildren(tcb);
@@ -119,6 +172,11 @@ void group_leave(FAR _TCB *tcb)
sched_free(group);
}
+#endif
+
+ /* In any event, we can detach the group from the TCB so we won't do
+ * this again.
+ */
tcb->group = NULL;
}
diff --git a/nuttx/sched/os_internal.h b/nuttx/sched/os_internal.h
index ee5ada165..8ce99bc44 100644
--- a/nuttx/sched/os_internal.h
+++ b/nuttx/sched/os_internal.h
@@ -273,12 +273,14 @@ int task_deletecurrent(void);
int task_reparent(pid_t ppid, pid_t chpid);
#ifdef HAVE_TASK_GROUP
-int group_create(FAR _TCB *tcb);
-void group_join(FAR _TCB *tcb);
+int group_allocate(FAR _TCB *tcb);
+int group_initialize(FAR _TCB *tcb);
+int group_join(FAR _TCB *tcb);
void group_leave(FAR _TCB *tcb);
#else
-# define group_create(tcb)
-# define group_join(tcb)
+# define group_allocate(tcb) (0)
+# define group_initialize(tcb) (0)
+# define group_join(tcb) (0)
# define group_leave(tcb)
#endif
diff --git a/nuttx/sched/os_start.c b/nuttx/sched/os_start.c
index 244aec967..3aecc7efb 100644
--- a/nuttx/sched/os_start.c
+++ b/nuttx/sched/os_start.c
@@ -202,9 +202,6 @@ const tasklist_t g_tasklisttable[NUM_TASK_STATES] =
*/
static FAR _TCB g_idletcb;
-#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS)
-static struct task_group_s g_idlegroup;
-#endif
/* This is the name of the idle task */
@@ -283,14 +280,6 @@ void os_start(void)
g_idletcb.argv[0] = (char*)g_idlename;
#endif /* CONFIG_TASK_NAME_SIZE */
- /* Join the IDLE group */
-
-#ifdef HAVE_TASK_GROUP
- g_idlegroup.tg_crefs = 1;
- g_idlegroup.tg_flags = GROUP_FLAG_NOCLDWAIT;
- g_idletcb.group = &g_idlegroup;
-#endif
-
/* Then add the idle task's TCB to the head of the ready to run list */
dq_addfirst((FAR dq_entry_t*)&g_idletcb, (FAR dq_queue_t*)&g_readytorun);
@@ -447,6 +436,14 @@ void os_start(void)
lib_initialize();
}
+ /* Create the IDLE group and suppress child status */
+
+#ifdef HAVE_TASK_GROUP
+ (void)group_allocate(&g_idletcb);
+ (void)group_initialize(&g_idletcb);
+ g_idletcb.group->tg_flags = GROUP_FLAG_NOCLDWAIT;
+#endif
+
/* Create stdout, stderr, stdin on the IDLE task. These will be
* inherited by all of the threads created by the IDLE task.
*/
diff --git a/nuttx/sched/pthread_create.c b/nuttx/sched/pthread_create.c
index e37c06892..89a2feb00 100644
--- a/nuttx/sched/pthread_create.c
+++ b/nuttx/sched/pthread_create.c
@@ -246,13 +246,13 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
{
FAR _TCB *ptcb;
FAR join_t *pjoin;
- int ret;
int priority;
#if CONFIG_RR_INTERVAL > 0
int policy;
#endif
int errcode;
pid_t pid;
+ int ret;
/* If attributes were not supplied, use the default attributes */
@@ -269,10 +269,17 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
return ENOMEM;
}
- /* Join the parent's task group */
+ /* Bind the parent's group to the new TCB (we have not yet joined the
+ * group).
+ */
#ifdef HAVE_TASK_GROUP
- group_join(ptcb);
+ ret = group_bind(ptcb);
+ if (ret < 0)
+ {
+ errcode = ENOMEM;
+ goto errout_with_tcb;
+ }
#endif
/* Share the address environment of the parent task. NOTE: Only tasks
@@ -376,6 +383,17 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
pthread_argsetup(ptcb, arg);
+ /* Join the parent's task group */
+
+#ifdef HAVE_TASK_GROUP
+ ret = group_join(ptcb);
+ if (ret < 0)
+ {
+ errcode = ENOMEM;
+ goto errout_with_join;
+ }
+#endif
+
/* Attach the join info to the TCB. */
ptcb->joininfo = (void*)pjoin;
diff --git a/nuttx/sched/task_create.c b/nuttx/sched/task_create.c
index f2aeeeec0..bb309444b 100644
--- a/nuttx/sched/task_create.c
+++ b/nuttx/sched/task_create.c
@@ -120,10 +120,10 @@ static int thread_create(const char *name, uint8_t ttype, int priority,
goto errout;
}
- /* Create a new task group */
+ /* Allocate a new task group */
#ifdef HAVE_TASK_GROUP
- ret = group_create(tcb);
+ ret = group_allocate(tcb);
if (ret < 0)
{
errcode = -ret;
@@ -160,7 +160,7 @@ static int thread_create(const char *name, uint8_t ttype, int priority,
/* Initialize the task control block */
ret = task_schedsetup(tcb, priority, task_start, entry, ttype);
- if (ret != OK)
+ if (ret < OK)
{
errcode = -ret;
goto errout_with_tcb;
@@ -170,6 +170,17 @@ static int thread_create(const char *name, uint8_t ttype, int priority,
(void)task_argsetup(tcb, name, argv);
+ /* Now we have enough in place that we can join the group */
+
+#ifdef HAVE_TASK_GROUP
+ ret = group_initialize(tcb);
+ if (ret < 0)
+ {
+ errcode = -ret;
+ goto errout_with_tcb;
+ }
+#endif
+
/* Get the assigned pid before we start the task */
pid = (int)tcb->pid;
diff --git a/nuttx/sched/task_exithook.c b/nuttx/sched/task_exithook.c
index 30ce41f71..36836301c 100644
--- a/nuttx/sched/task_exithook.c
+++ b/nuttx/sched/task_exithook.c
@@ -207,7 +207,7 @@ static inline void task_sigchild(FAR _TCB *ptcb, FAR _TCB *ctcb, int status)
*/
#ifdef CONFIG_SCHED_CHILD_STATUS
- if (ctcb->group->tg_crefs == 1)
+ if (ctcb->group->tg_nmembers == 1)
#else
if ((ctcb->flags & TCB_FLAG_TTYPE_MASK) == TCB_FLAG_TTYPE_TASK)
#endif
diff --git a/nuttx/sched/task_init.c b/nuttx/sched/task_init.c
index 5ba6b7e7d..6ae643948 100644
--- a/nuttx/sched/task_init.c
+++ b/nuttx/sched/task_init.c
@@ -126,7 +126,7 @@ int task_init(FAR _TCB *tcb, const char *name, int priority,
/* Create a new task group */
#ifdef HAVE_TASK_GROUP
- ret = group_create(tcb);
+ ret = group_allocate(tcb);
if (ret < 0)
{
errcode = -ret;
@@ -168,6 +168,17 @@ int task_init(FAR _TCB *tcb, const char *name, int priority,
/* Setup to pass parameters to the new task */
(void)task_argsetup(tcb, name, argv);
+
+ /* Now we have enough in place that we can join the group */
+
+#ifdef HAVE_TASK_GROUP
+ ret = group_initialize(tcb);
+ if (ret < 0)
+ {
+ errcode = -ret;
+ goto errout_with_env;
+ }
+#endif
return OK;
errout_with_env: