aboutsummaryrefslogtreecommitdiff
path: root/nuttx/sched
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/sched')
-rw-r--r--nuttx/sched/Kconfig27
-rw-r--r--nuttx/sched/Makefile34
-rw-r--r--nuttx/sched/env_clearenv.c8
-rw-r--r--nuttx/sched/env_dup.c68
-rw-r--r--nuttx/sched/env_dupenv.c112
-rw-r--r--nuttx/sched/env_findvar.c33
-rw-r--r--nuttx/sched/env_getenv.c14
-rw-r--r--nuttx/sched/env_internal.h36
-rw-r--r--nuttx/sched/env_release.c67
-rw-r--r--nuttx/sched/env_removevar.c56
-rw-r--r--nuttx/sched/env_setenv.c59
-rw-r--r--nuttx/sched/env_unsetenv.c62
-rw-r--r--nuttx/sched/group_childstatus.c (renamed from nuttx/sched/task_childstatus.c)129
-rw-r--r--nuttx/sched/group_create.c276
-rw-r--r--nuttx/sched/group_find.c (renamed from nuttx/sched/env_share.c)116
-rw-r--r--nuttx/sched/group_internal.h (renamed from nuttx/sched/sched_setuppthreadfiles.c)124
-rw-r--r--nuttx/sched/group_join.c227
-rw-r--r--nuttx/sched/group_leave.c366
-rw-r--r--nuttx/sched/group_setupidlefiles.c (renamed from nuttx/sched/sched_setupidlefiles.c)34
-rw-r--r--nuttx/sched/group_setupstreams.c (renamed from nuttx/sched/sched_setupstreams.c)45
-rw-r--r--nuttx/sched/group_setuptaskfiles.c (renamed from nuttx/sched/sched_setuptaskfiles.c)105
-rw-r--r--nuttx/sched/group_signal.c163
-rw-r--r--nuttx/sched/mq_sndinternal.c2
-rw-r--r--nuttx/sched/os_internal.h35
-rw-r--r--nuttx/sched/os_start.c23
-rw-r--r--nuttx/sched/pthread_create.c74
-rw-r--r--nuttx/sched/pthread_join.c2
-rw-r--r--nuttx/sched/sched_getfiles.c7
-rw-r--r--nuttx/sched/sched_getsockets.c7
-rw-r--r--nuttx/sched/sched_getstreams.c7
-rw-r--r--nuttx/sched/sched_releasetcb.c17
-rw-r--r--nuttx/sched/sched_waitid.c149
-rw-r--r--nuttx/sched/sched_waitpid.c167
-rw-r--r--nuttx/sched/sig_action.c27
-rw-r--r--nuttx/sched/task_create.c41
-rw-r--r--nuttx/sched/task_exithook.c318
-rw-r--r--nuttx/sched/task_init.c66
-rw-r--r--nuttx/sched/task_posixspawn.c1
-rw-r--r--nuttx/sched/task_reparent.c177
-rw-r--r--nuttx/sched/task_setup.c58
-rw-r--r--nuttx/sched/task_start.c9
-rw-r--r--nuttx/sched/task_starthook.c (renamed from nuttx/sched/sched_releasefiles.c)92
-rw-r--r--nuttx/sched/task_vfork.c9
-rw-r--r--nuttx/sched/timer_initialize.c2
44 files changed, 2476 insertions, 975 deletions
diff --git a/nuttx/sched/Kconfig b/nuttx/sched/Kconfig
index fe9a88085..097dd1993 100644
--- a/nuttx/sched/Kconfig
+++ b/nuttx/sched/Kconfig
@@ -124,6 +124,13 @@ config PREALLOC_CHILDSTATUS
sa.sa_flags = SA_NOCLDWAIT;
int ret = sigaction(SIGCHLD, &sa, NULL);
+config DEBUG_CHILDSTATUS
+ bool "Enable Child Status Debug Output"
+ default n
+ depends on SCHED_CHILD_STATUS && DEBUG
+ ---help---
+ Very detailed... I am sure that you do not want this.
+
config JULIAN_TIME
bool "Enables Julian time conversions"
default n
@@ -289,6 +296,16 @@ config SCHED_WAITPID
compliant) and will enable the waitid() and wait() interfaces as
well.
+config SCHED_STARTHOOK
+ bool "Enable startup hook"
+ default n
+ ---help---
+ Enable a non-standard, internal OS API call task_starthook().
+ task_starthook() registers a function that will be called on task
+ startup before that actual task entry point is called. The
+ starthook is useful, for example, for setting up automatic
+ configuration of C++ constructors.
+
config SCHED_ATEXIT
bool "Enable atexit() API"
default n
@@ -379,21 +396,11 @@ config DISABLE_MQUEUE
depends on DISABLE_OS_API
default n
-config DISABLE_MOUNTPOINT
- bool "Disable support for mount points"
- depends on DISABLE_OS_API
- default n
-
config DISABLE_ENVIRON
bool "Disable environment variable support"
depends on DISABLE_OS_API
default n
-config DISABLE_POLL
- bool "Disable driver poll interfaces"
- depends on DISABLE_OS_API
- default n
-
if !DISABLE_SIGNALS
comment "Signal Numbers"
diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile
index 1ad244450..961560176 100644
--- a/nuttx/sched/Makefile
+++ b/nuttx/sched/Makefile
@@ -39,9 +39,7 @@ ASRCS =
AOBJS = $(ASRCS:.S=$(OBJEXT))
MISC_SRCS = os_start.c os_bringup.c errno_getptr.c errno_get.c errno_set.c
-MISC_SRCS += sched_garbage.c sched_setupstreams.c sched_getfiles.c sched_getsockets.c
-MISC_SRCS += sched_getstreams.c sched_setupidlefiles.c sched_setuptaskfiles.c
-MISC_SRCS += sched_setuppthreadfiles.c sched_releasefiles.c
+MISC_SRCS += sched_garbage.c sched_getfiles.c sched_getsockets.c sched_getstreams.c
TSK_SRCS = prctl.c task_create.c task_init.c task_setup.c task_activate.c
TSK_SRCS += task_start.c task_delete.c task_deletecurrent.c task_exithook.c
@@ -56,6 +54,10 @@ TSK_SRCS += task_posixspawn.c
endif
endif
+ifeq ($(CONFIG_SCHED_STARTHOOK),y)
+TSK_SRCS += task_starthook.c
+endif
+
SCHED_SRCS = sched_setparam.c sched_setpriority.c sched_getparam.c
SCHED_SRCS += sched_setscheduler.c sched_getscheduler.c
SCHED_SRCS += sched_yield.c sched_rrgetinterval.c sched_foreach.c
@@ -73,21 +75,28 @@ ifeq ($(CONFIG_PRIORITY_INHERITANCE),y)
SCHED_SRCS += sched_reprioritize.c
endif
+ifeq ($(CONFIG_SCHED_WAITPID),y)
+SCHED_SRCS += sched_waitpid.c
ifeq ($(CONFIG_SCHED_HAVE_PARENT),y)
-SCHED_SRCS += task_reparent.c
-ifeq ($(CONFIG_SCHED_CHILD_STATUS),y)
-SCHED_SRCS += task_childstatus.c
+SCHED_SRCS += sched_waitid.c sched_wait.c
endif
endif
-ifeq ($(CONFIG_SCHED_WAITPID),y)
-SCHED_SRCS += sched_waitpid.c
+GRP_SRCS = group_create.c group_join.c group_leave.c group_find.c
+GRP_SRCS += group_setupstreams.c group_setupidlefiles.c group_setuptaskfiles.c
+
ifeq ($(CONFIG_SCHED_HAVE_PARENT),y)
-SCHED_SRCS += sched_waitid.c sched_wait.c
+GRP_SRCS += task_reparent.c
+ifeq ($(CONFIG_SCHED_CHILD_STATUS),y)
+GRP_SRCS += group_childstatus.c
endif
endif
-ENV_SRCS = env_getenvironptr.c env_dup.c env_share.c env_release.c
+ifneq ($(CONFIG_DISABLE_SIGNALS),y)
+GRP_SRCS += group_signal.c
+endif
+
+ENV_SRCS = env_getenvironptr.c env_dup.c env_release.c
ENV_SRCS += env_findvar.c env_removevar.c
ENV_SRCS += env_clearenv.c env_getenv.c env_putenv.c env_setenv.c env_unsetenv.c
@@ -169,8 +178,9 @@ IRQ_SRCS = irq_initialize.c irq_attach.c irq_dispatch.c irq_unexpectedisr.c
KMM_SRCS = kmm_initialize.c kmm_addregion.c kmm_semaphore.c
KMM_SRCS = kmm_kmalloc.c kmm_kzalloc.c kmm_krealloc.c kmm_kfree.c
-CSRCS = $(MISC_SRCS) $(TSK_SRCS) $(SCHED_SRCS) $(WDOG_SRCS) $(TIME_SRCS) \
- $(SEM_SRCS) $(TIMER_SRCS) $(WORK_SRCS) $(PGFILL_SRCS) $(IRQ_SRCS)
+CSRCS = $(MISC_SRCS) $(TSK_SRCS) $(GRP_SRCS) $(SCHED_SRCS) $(WDOG_SRCS)
+CSRCS += $(TIME_SRCS) $(SEM_SRCS) $(TIMER_SRCS) $(WORK_SRCS) $(PGFILL_SRCS)
+CSRCS += $(IRQ_SRCS)
ifneq ($(CONFIG_DISABLE_CLOCK),y)
CSRCS += $(CLOCK_SRCS)
diff --git a/nuttx/sched/env_clearenv.c b/nuttx/sched/env_clearenv.c
index 75890f3bc..062fd60ed 100644
--- a/nuttx/sched/env_clearenv.c
+++ b/nuttx/sched/env_clearenv.c
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/env_clearenv.c
*
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -74,7 +74,11 @@
int clearenv(void)
{
- return env_release((FAR _TCB*)g_readytorun.head);
+ FAR _TCB *tcb = (FAR _TCB*)g_readytorun.head;
+ DEBUGASSERT(tcb->group);
+
+ env_release(tcb->group);
+ return OK;
}
#endif /* CONFIG_DISABLE_ENVIRON */
diff --git a/nuttx/sched/env_dup.c b/nuttx/sched/env_dup.c
index 033348411..3b653b010 100644
--- a/nuttx/sched/env_dup.c
+++ b/nuttx/sched/env_dup.c
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/env_dup.c
*
- * Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -68,8 +68,8 @@
* exact duplicate of the parent task's environment.
*
* Parameters:
- * ptcb The tcb to receive the newly allocated copy of the parspecifiedent
- * TCB's environment structure with reference count equal to one
+ * group The child task group to receive the newly allocated copy of the
+ * parent task groups environment structure.
*
* Return Value:
* zero on success
@@ -79,50 +79,42 @@
*
****************************************************************************/
-int env_dup(FAR _TCB *ptcb)
+int env_dup(FAR struct task_group_s *group)
{
+ FAR _TCB *ptcb = (FAR _TCB*)g_readytorun.head;
+ FAR char *envp = NULL;
+ size_t envlen;
int ret = OK;
- if (!ptcb )
- {
- ret = -EINVAL;
- }
- else
- {
- FAR _TCB *parent = (FAR _TCB*)g_readytorun.head;
- environ_t *envp = NULL;
- /* Pre-emption must be disabled throughout the following because the
- * environment may be shared.
- */
+ DEBUGASSERT(group && ptcb && ptcb->group);
- sched_lock();
+ /* Pre-emption must be disabled throughout the following because the
+ * environment may be shared.
+ */
- /* Does the parent task have an environment? */
+ sched_lock();
- if (parent->envp)
- {
- /* Yes..The parent task has an environment, duplicate it */
-
- size_t envlen = parent->envp->ev_alloc;
- envp = (environ_t*)kmalloc(SIZEOF_ENVIRON_T( envlen ));
- if (!envp)
- {
- ret = -ENOMEM;
- }
- else
- {
- envp->ev_crefs = 1;
- envp->ev_alloc = envlen;
- memcpy( envp->ev_env, parent->envp->ev_env, envlen );
- }
- }
+ /* Does the parent task have an environment? */
- /* Save the cloned environment in the new TCB */
+ if (ptcb->group && ptcb->group->tg_envp)
+ {
+ /* Yes..The parent task has an environment, duplicate it */
- ptcb->envp = envp;
- sched_unlock();
- }
+ envlen = ptcb->group->tg_envsize;
+ envp = (FAR char *)kmalloc(envlen);
+ if (!envp)
+ {
+ ret = -ENOMEM;
+ }
+ else
+ {
+ group->tg_envsize = envlen;
+ group->tg_envp = envp;
+ memcpy(envp, ptcb->group->tg_envp, envlen);
+ }
+ }
+ sched_unlock();
return ret;
}
diff --git a/nuttx/sched/env_dupenv.c b/nuttx/sched/env_dupenv.c
deleted file mode 100644
index 32bf6a433..000000000
--- a/nuttx/sched/env_dupenv.c
+++ /dev/null
@@ -1,112 +0,0 @@
-/****************************************************************************
- * eched/env_dupenv.c
- *
- * Copyright (C) 2007, 2009, 2011 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>
-
-#ifndef CONFIG_DISABLE_ENVIRON
-
-#include <sys/types.h>
-#include <sched.h>
-
-#include <nuttx/kmalloc.h>
-
-#include "os_internal.h"
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: dupenv
- *
- * Description:
- * Copy the internal environment structure of a task. This is the action
- * that is performed when a new task is created: The new task has a private,
- * exact duplicate of the parent task's environment.
- *
- * Parameters:
- * None
- *
- * Return Value:
- * A pointer to a newly allocated copy of the specified TCB's environment
- * structure with reference count equal to one.
- *
- * Assumptions:
- * Not called from an interrupt handler.
- *
- ****************************************************************************/
-
-FAR environ_t *dupenv(FAR _TCB *ptcb)
-{
- environ_t *envp = NULL;
-
- /* Pre-emption must be disabled throughout the following because the
- * environment may be shared.
- */
-
- sched_lock();
-
- /* Does the parent task have an environment? */
-
- if (ptcb->envp)
- {
- /* Yes..The parent task has an environment, duplicate it */
-
- size_t envlen = ptcb->envp->ev_alloc
- envp = (environ_t*)kmalloc(SIZEOF_ENVIRON_T( envlen ));
- if (envp)
- {
- envp->ev_crefs = 1;
- envp->ev_alloc = envlen;
- memcmp( envp->ev_env, ptcb->envp->ev_env, envlen );
- }
- }
-
- sched_unlock();
- return envp;
-}
-
-#endif /* CONFIG_DISABLE_ENVIRON */
-
-
-
diff --git a/nuttx/sched/env_findvar.c b/nuttx/sched/env_findvar.c
index a8e94180c..a744c6c3a 100644
--- a/nuttx/sched/env_findvar.c
+++ b/nuttx/sched/env_findvar.c
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/env_findvar.c
*
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -85,7 +85,7 @@ static bool env_cmpname(const char *pszname, const char *peqname)
* specified name.
*
* Parameters:
- * envp The environment structre to be searched.
+ * group The task group containging environment array to be searched.
* pname The variable name to find
*
* Return Value:
@@ -97,32 +97,25 @@ static bool env_cmpname(const char *pszname, const char *peqname)
*
****************************************************************************/
-FAR char *env_findvar(environ_t *envp, const char *pname)
+FAR char *env_findvar(FAR struct task_group_s *group, const char *pname)
{
- char *ret = NULL;
+ char *ptr;
+ char *end;
/* Verify input parameters */
- if (envp && pname)
- {
- char *ptr;
- char *end = &envp->ev_env[envp->ev_alloc];
-
- /* Search for a name=value string with matching name */
+ DEBUGASSERT(group && pname);
- for (ptr = envp->ev_env;
- ptr < end && !env_cmpname( pname, ptr);
- ptr += (strlen(ptr) + 1));
+ /* Search for a name=value string with matching name */
- /* Check for success */
+ end = &group->tg_envp[group->tg_envsize];
+ for (ptr = group->tg_envp;
+ ptr < end && !env_cmpname(pname, ptr);
+ ptr += (strlen(ptr) + 1));
- if (ptr < end)
- {
- ret = ptr;
- }
- }
+ /* Check for success */
- return ret;
+ return (ptr < end) ? ptr : NULL;
}
#endif /* CONFIG_DISABLE_ENVIRON */
diff --git a/nuttx/sched/env_getenv.c b/nuttx/sched/env_getenv.c
index ee8d798b1..4709bc380 100644
--- a/nuttx/sched/env_getenv.c
+++ b/nuttx/sched/env_getenv.c
@@ -1,7 +1,7 @@
/****************************************************************************
* env_getenv.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -77,10 +77,10 @@
FAR char *getenv(const char *name)
{
- FAR _TCB *rtcb;
- FAR environ_t *envp;
- FAR char *pvar;
- FAR char *pvalue = NULL;
+ FAR _TCB *rtcb;
+ FAR struct task_group_s *group;
+ FAR char *pvar;
+ FAR char *pvalue = NULL;
int ret = OK;
/* Verify that a string was passed */
@@ -95,11 +95,11 @@ FAR char *getenv(const char *name)
sched_lock();
rtcb = (FAR _TCB*)g_readytorun.head;
- envp = rtcb->envp;
+ group = rtcb->group;
/* Check if the variable exists */
- if ( !envp || (pvar = env_findvar(envp, name)) == NULL)
+ if ( !group || (pvar = env_findvar(group, name)) == NULL)
{
ret = ENOENT;
goto errout_with_lock;
diff --git a/nuttx/sched/env_internal.h b/nuttx/sched/env_internal.h
index 5370da059..e02bf289d 100644
--- a/nuttx/sched/env_internal.h
+++ b/nuttx/sched/env_internal.h
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/env_internal.h
*
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -49,10 +49,9 @@
****************************************************************************/
#ifdef CONFIG_DISABLE_ENVIRON
-# define env_dup(ptcb) (0)
-# define env_share(ptcb) (0)
-# define env_release(ptcb) (0)
-#endif
+# define env_dup(group) (0)
+# define env_release(group) (0)
+#else
/****************************************************************************
* Public Type Declarations
@@ -62,34 +61,33 @@
* Public Variables
****************************************************************************/
-/****************************************************************************
- * Public Function Prototypes
- ****************************************************************************/
-
#ifdef __cplusplus
#define EXTERN extern "C"
-extern "C" {
+extern "C"
+{
#else
#define EXTERN extern
#endif
-#ifndef CONFIG_DISABLE_ENVIRON
-/* functions used by the task/pthread creation and destruction logic */
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
-EXTERN int env_dup(FAR _TCB *ptcb);
-EXTERN int env_share(FAR _TCB *ptcb);
-EXTERN int env_release(FAR _TCB *ptcb);
+/* Functions used by the task/pthread creation and destruction logic */
-/* functions used internally by the environment handling logic */
+int env_dup(FAR struct task_group_s *group);
+void env_release(FAR struct task_group_s *group);
-EXTERN FAR char *env_findvar(environ_t *envp, const char *pname);
-EXTERN int env_removevar(environ_t *envp, char *pvar);
-#endif
+/* Functions used internally by the environment handling logic */
+
+FAR char *env_findvar(FAR struct task_group_s *group, FAR const char *pname);
+int env_removevar(FAR struct task_group_s *group, FAR char *pvar);
#undef EXTERN
#ifdef __cplusplus
}
#endif
+#endif /* !CONFIG_DISABLE_ENVIRON */
#endif /* __SCHED_ENV_INTERNAL_H */
diff --git a/nuttx/sched/env_release.c b/nuttx/sched/env_release.c
index 8bc8d2205..aebb1f7e8 100644
--- a/nuttx/sched/env_release.c
+++ b/nuttx/sched/env_release.c
@@ -1,7 +1,7 @@
/****************************************************************************
- * sched/env_clearenv.c
+ * sched/env_release.c
*
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -58,65 +58,42 @@
* Name: env_release
*
* Description:
- * The env_release() function clears the environment of all name-value
- * pairs and sets the value of the external variable environ to NULL.
+ * env_release() is called only from group_leave() when the last member of
+ * a task group exits. The env_release() function clears the environment
+ * of all name-value pairs and sets the value of the external variable
+ * environ to NULL.
*
* Parameters:
- * ptcb Identifies the TCB containing the environment structure
+ * group Identifies the task group containing the environment structure
+ * to be released.
*
* Return Value:
- * zero on success
+ * None
*
* Assumptions:
* Not called from an interrupt handler
*
****************************************************************************/
-int env_release(FAR _TCB *ptcb)
+void env_release(FAR struct task_group_s *group)
{
- int ret = OK;
+ DEBUGASSERT(group);
- if (!ptcb)
- {
- ret = -EINVAL;
- }
- else
- {
- FAR environ_t *envp;
-
- /* Examine the environ data in the TCB. Preemption is disabled because the
- * the environment could be shared among threads.
- */
-
- sched_lock();
- envp = ptcb->envp;
- if (ptcb->envp)
- {
- /* Check the reference count on the environment structure */
-
- if (envp->ev_crefs <= 1)
- {
- /* Decrementing the reference count will destroy the environment */
+ /* Free any allocate environment strings */
- sched_free(envp);
- }
- else
- {
- /* The environment will persist after decrementing the reference
- * count */
-
- envp->ev_crefs--;
- }
-
- /* In any case, the environment is no longer accessible on this thread */
-
- ptcb->envp = NULL;
- }
+ if (group->tg_envp)
+ {
+ /* Free the environment */
- sched_unlock();
+ sched_free(group->tg_envp);
}
- return ret;
+ /* In any event, make sure that all environment-related varialbles in the
+ * task group structure are reset to initial values.
+ */
+
+ group->tg_envsize = 0;
+ group->tg_envp = NULL;
}
#endif /* CONFIG_DISABLE_ENVIRON */
diff --git a/nuttx/sched/env_removevar.c b/nuttx/sched/env_removevar.c
index e96aa7a37..811e6079e 100644
--- a/nuttx/sched/env_removevar.c
+++ b/nuttx/sched/env_removevar.c
@@ -59,7 +59,7 @@
* Remove the referenced name=value pair from the environment
*
* Parameters:
- * envp The environment containing the name=value pair
+ * group The task group with the environment containing the name=value pair
* pvar A pointer to the name=value pair in the restroom
*
* Return Value:
@@ -72,42 +72,44 @@
*
****************************************************************************/
-int env_removevar(environ_t *envp, char *pvar)
+int env_removevar(FAR struct task_group_s *group, FAR char *pvar)
{
+ FAR char *end; /* Pointer to the end+1 of the environment */
+ int alloc; /* Size of the allocated environment */
int ret = ERROR;
- if (envp && pvar)
- {
- /* Verify that the pointer lies within the environment region */
- int alloc = envp->ev_alloc; /* Size of the allocated environment */
- char *end = &envp->ev_env[alloc]; /* Pointer to the end+1 of the environment */
+ DEBUGASSERT(group && pvar);
- if (pvar >= envp->ev_env && pvar < end)
- {
- /* Set up for the removal */
+ /* Verify that the pointer lies within the environment region */
- int len = strlen(pvar) + 1; /* Length of name=value string to remove */
- char *src = &pvar[len]; /* Address of name=value string after */
- char *dest = pvar; /* Location to move the next string */
- int count = end - src; /* Number of bytes to move (might be zero) */
+ alloc = group->tg_envsize; /* Size of the allocated environment */
+ end = &group->tg_envp[alloc]; /* Pointer to the end+1 of the environment */
- /* Move all of the environment strings after the removed one 'down.'
- * this is inefficient, but robably not high duty.
- */
+ if (pvar >= group->tg_envp && pvar < end)
+ {
+ /* Set up for the removal */
- while (count-- > 0)
- {
- *dest++ = *src++;
- }
+ int len = strlen(pvar) + 1; /* Length of name=value string to remove */
+ char *src = &pvar[len]; /* Address of name=value string after */
+ char *dest = pvar; /* Location to move the next string */
+ int count = end - src; /* Number of bytes to move (might be zero) */
- /* Then set to the new allocation size. The caller is expected to
- * call realloc at some point but we don't do that here because the
- * caller may add more stuff to the environment.
- */
+ /* Move all of the environment strings after the removed one 'down.'
+ * this is inefficient, but robably not high duty.
+ */
- envp->ev_alloc -= len;
- ret = OK;
+ while (count-- > 0)
+ {
+ *dest++ = *src++;
}
+
+ /* Then set to the new allocation size. The caller is expected to
+ * call realloc at some point but we don't do that here because the
+ * caller may add more stuff to the environment.
+ */
+
+ group->tg_envsize -= len;
+ ret = OK;
}
return ret;
diff --git a/nuttx/sched/env_setenv.c b/nuttx/sched/env_setenv.c
index c186241ef..cfde71604 100644
--- a/nuttx/sched/env_setenv.c
+++ b/nuttx/sched/env_setenv.c
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/env_setenv.c
*
- * Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -83,12 +83,14 @@
*
****************************************************************************/
-int setenv(const char *name, const char *value, int overwrite)
+int setenv(FAR const char *name, FAR const char *value, int overwrite)
{
- FAR _TCB *rtcb;
- FAR environ_t *envp;
- FAR char *pvar;
- int varlen;
+ FAR _TCB *rtcb;
+ FAR struct task_group_s *group;
+ FAR char *pvar;
+ FAR char *newenvp;
+ int newsize;
+ int varlen;
int ret = OK;
/* Verify input parameter */
@@ -122,14 +124,15 @@ int setenv(const char *name, const char *value, int overwrite)
/* Get a reference to the thread-private environ in the TCB.*/
sched_lock();
- rtcb = (FAR _TCB*)g_readytorun.head;
- envp = rtcb->envp;
+ rtcb = (FAR _TCB*)g_readytorun.head;
+ group = rtcb->group;
+ DEBUGASSERT(group);
- /* Check if the variable alreay exists */
+ /* Check if the variable already exists */
- if ( envp && (pvar = env_findvar(envp, name)) != NULL)
+ if (group->tg_envp && (pvar = env_findvar(group, name)) != NULL)
{
- /* It does! Do we have permission to overwrite the existing value? */
+ /* It does! Do we have permission to overwrite the existing value? */
if (!overwrite)
{
@@ -144,7 +147,7 @@ int setenv(const char *name, const char *value, int overwrite)
* the environment buffer; this will happen below.
*/
- (void)env_removevar(envp, pvar);
+ (void)env_removevar(group, pvar);
}
/* Get the size of the new name=value string. The +2 is for the '=' and for
@@ -155,43 +158,39 @@ int setenv(const char *name, const char *value, int overwrite)
/* Then allocate or reallocate the environment buffer */
- if (envp)
+ if (group->tg_envp)
{
- int alloc = envp->ev_alloc;
- environ_t *tmp = (environ_t*)krealloc(envp, SIZEOF_ENVIRON_T(alloc + varlen));
- if (!tmp)
+ newsize = group->tg_envsize + varlen;
+ newenvp = (FAR char *)krealloc(group->tg_envp, newsize);
+ if (!newenvp)
{
ret = ENOMEM;
goto errout_with_lock;
}
- envp = tmp;
- envp->ev_alloc = alloc + varlen;
- pvar = &envp->ev_env[alloc];
+ pvar = &newenvp[group->tg_envsize];
}
else
{
- envp = (environ_t*)kmalloc(SIZEOF_ENVIRON_T(varlen));
- if (!envp)
+ newsize = varlen;
+ newenvp = (FAR char *)kmalloc(varlen);
+ if (!newenvp)
{
ret = ENOMEM;
goto errout_with_lock;
}
- envp->ev_crefs = 1;
- envp->ev_alloc = varlen;
- pvar = envp->ev_env;
+ pvar = newenvp;
}
- /* Now, put the new name=value string into the environment buffer */
+ /* Save the new buffer and size */
- sprintf(pvar, "%s=%s", name, value);
+ group->tg_envp = newenvp;
+ group->tg_envsize = newsize;
- /* Save the new environment pointer (it might have changed due to allocation or
- * reallocation.
- */
+ /* Now, put the new name=value string into the environment buffer */
- rtcb->envp = envp;
+ sprintf(pvar, "%s=%s", name, value);
sched_unlock();
return OK;
diff --git a/nuttx/sched/env_unsetenv.c b/nuttx/sched/env_unsetenv.c
index 52469fac9..8206a4ece 100644
--- a/nuttx/sched/env_unsetenv.c
+++ b/nuttx/sched/env_unsetenv.c
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/env_unsetenv.c
*
- * Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -75,61 +75,47 @@
*
****************************************************************************/
-int unsetenv(const char *name)
+int unsetenv(FAR const char *name)
{
- FAR _TCB *rtcb;
- FAR environ_t *envp;
- FAR char *pvar;
+ FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
+ FAR struct task_group_s *group = rtcb->group;
+ FAR char *pvar;
+ FAR char *newenvp;
+ int newsize;
int ret = OK;
- /* Verify input parameter */
-
- if (!name)
- {
- ret = EINVAL;
- goto errout;
- }
-
- /* Get a reference to the thread-private environ in the TCB.*/
-
- sched_lock();
- rtcb = (FAR _TCB*)g_readytorun.head;
- envp = rtcb->envp;
+ DEBUGASSERT(name && group);
/* Check if the variable exists */
- if ( envp && (pvar = env_findvar(envp, name)) != NULL)
+ sched_lock();
+ if (group && (pvar = env_findvar(group, name)) != NULL)
{
- int alloc;
- environ_t *tmp;
-
/* It does! Remove the name=value pair from the environment. */
- (void)env_removevar(envp, pvar);
+ (void)env_removevar(group, pvar);
/* Reallocate the new environment buffer */
- alloc = envp->ev_alloc;
- tmp = (environ_t*)krealloc(envp, SIZEOF_ENVIRON_T(alloc));
- if (!tmp)
+ newsize = group->tg_envsize;
+ newenvp = (FAR char *)krealloc(group->tg_envp, newsize);
+ if (!newenvp)
{
- ret = ENOMEM;
- goto errout_with_lock;
+ set_errno(ENOMEM);
+ ret = ERROR;
}
+ else
+ {
+ /* Save the new environment pointer (it might have changed due to
+ * reallocation.
+ */
- /* Save the new environment pointer (it might have changed due to reallocation. */
-
- rtcb->envp = tmp;
+ group->tg_envp = newenvp;
+ }
}
sched_unlock();
- return OK;
-
-errout_with_lock:
- sched_unlock();
-errout:
- errno = ret;
- return ERROR;
+ return ret;
}
#endif /* CONFIG_DISABLE_ENVIRON */
diff --git a/nuttx/sched/task_childstatus.c b/nuttx/sched/group_childstatus.c
index 0f6d36c29..ef42b6c34 100644
--- a/nuttx/sched/task_childstatus.c
+++ b/nuttx/sched/group_childstatus.c
@@ -1,5 +1,5 @@
/*****************************************************************************
- * sched/task_childstatus.c
+ * sched/group_childstatus.c
*
* Copyright (C) 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@@ -44,6 +44,7 @@
#include <debug.h>
#include "os_internal.h"
+#include "group_internal.h"
#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS)
@@ -91,13 +92,13 @@ static struct child_pool_s g_child_pool;
*****************************************************************************/
/*****************************************************************************
- * Name: task_dumpchildren
+ * Name: group_dumpchildren
*
* Description:
* Dump all of the children when the part TCB list is modified.
*
* Parameters:
- * tcb - The parent TCB.
+ * group - The task group containing the child status.
*
* Return Value:
* None.
@@ -108,20 +109,21 @@ static struct child_pool_s g_child_pool;
*****************************************************************************/
#ifdef CONFIG_DEBUG_CHILDSTATUS
-static void task_dumpchildren(FAR _TCB *tcb, FAR const char *msg)
+static void group_dumpchildren(FAR struct task_group_s *group,
+ FAR const char *msg)
{
FAR struct child_status_s *child;
int i;
- dbg("Parent TCB=%p: %s\n", tcb, msg);
- for (i = 0, child = tcb->children; child; i++, child = child->flink)
+ dbg("Task group=%p: %s\n", group, msg);
+ for (i = 0, child = group->tg_children; child; i++, child = child->flink)
{
dbg(" %d. ch_flags=%02x ch_pid=%d ch_status=%d\n",
i, child->ch_flags, child->ch_pid, child->ch_status);
}
}
#else
-# task_dumpchildren(t,m)
+# define group_dumpchildren(t,m)
#endif
/*****************************************************************************
@@ -165,7 +167,7 @@ void task_initialize(void)
}
/*****************************************************************************
- * Name: task_allocchild
+ * Name: group_allocchild
*
* Description:
* Allocate a child status structure by removing the next entry from a
@@ -184,7 +186,7 @@ void task_initialize(void)
*
*****************************************************************************/
-FAR struct child_status_s *task_allocchild(void)
+FAR struct child_status_s *group_allocchild(void)
{
FAR struct child_status_s *ret;
@@ -201,7 +203,7 @@ FAR struct child_status_s *task_allocchild(void)
}
/*****************************************************************************
- * Name: task_freechild
+ * Name: group_freechild
*
* Description:
* Release a child status structure by returning it to a free list.
@@ -218,7 +220,7 @@ FAR struct child_status_s *task_allocchild(void)
*
*****************************************************************************/
-void task_freechild(FAR struct child_status_s *child)
+void group_freechild(FAR struct child_status_s *child)
{
/* Return the child status structure to the free list */
@@ -230,13 +232,13 @@ void task_freechild(FAR struct child_status_s *child)
}
/*****************************************************************************
- * Name: task_addchild
+ * Name: group_addchild
*
* Description:
* Add a child status structure in the given TCB.
*
* Parameters:
- * tcb - The TCB of the parent task to containing the child status.
+ * group - The task group for the child status.
* child - The structure to be added
*
* Return Value:
@@ -248,26 +250,27 @@ void task_freechild(FAR struct child_status_s *child)
*
*****************************************************************************/
-void task_addchild(FAR _TCB *tcb, FAR struct child_status_s *child)
+void group_addchild(FAR struct task_group_s *group,
+ FAR struct child_status_s *child)
{
/* Add the entry into the TCB list of children */
- child->flink = tcb->children;
- tcb->children = child;
+ child->flink = group->tg_children;
+ group->tg_children = child;
- task_dumpchildren(tcb, "task_addchild");
+ group_dumpchildren(group, "group_addchild");
}
/*****************************************************************************
- * Name: task_findchild
+ * Name: group_findchild
*
* Description:
- * Find a child status structure in the given TCB. A reference to the
- * child structure is returned, but the child remains the the TCB's list
- * of children.
+ * Find a child status structure in the given task group. A reference to
+ * the child structure is returned, but the child remains the the group's
+ * list of children.
*
* Parameters:
- * tcb - The TCB of the parent task to containing the child status.
+ * group - The ID of the parent task group to containing the child status.
* pid - The ID of the child to find.
*
* Return Value:
@@ -280,13 +283,16 @@ void task_addchild(FAR _TCB *tcb, FAR struct child_status_s *child)
*
*****************************************************************************/
-FAR struct child_status_s *task_findchild(FAR _TCB *tcb, pid_t pid)
+FAR struct child_status_s *group_findchild(FAR struct task_group_s *group,
+ pid_t pid)
{
FAR struct child_status_s *child;
+ DEBUGASSERT(group);
+
/* Find the status structure with the matching PID */
- for (child = tcb->children; child; child = child->flink)
+ for (child = group->tg_children; child; child = child->flink)
{
if (child->ch_pid == pid)
{
@@ -298,15 +304,51 @@ FAR struct child_status_s *task_findchild(FAR _TCB *tcb, pid_t pid)
}
/*****************************************************************************
- * Name: task_removechild
+ * Name: group_exitchild
*
* Description:
- * Remove one child structure from the TCB. The child is removed, but is
- * not yet freed. task_freechild must be called in order to free the child
- * status structure.
+ * Search for any child that has exitted.
*
* Parameters:
* tcb - The TCB of the parent task to containing the child status.
+ *
+ * Return Value:
+ * On success, a non-NULL pointer to a child status structure for the
+ * exited child. NULL is returned if not child has exited.
+ *
+ * Assumptions:
+ * Called during SIGCHLD processing in a safe context. No special precautions
+ * are required here.
+ *
+ *****************************************************************************/
+
+FAR struct child_status_s *group_exitchild(FAR struct task_group_s *group)
+{
+ FAR struct child_status_s *child;
+
+ /* Find the status structure of any child task that has exitted. */
+
+ for (child = group->tg_children; child; child = child->flink)
+ {
+ if ((child->ch_flags & CHILD_FLAG_EXITED) != 0)
+ {
+ return child;
+ }
+ }
+
+ return NULL;
+}
+
+/*****************************************************************************
+ * Name: group_removechild
+ *
+ * Description:
+ * Remove one child structure from a task group. The child is removed, but
+ * is not yet freed. group_freechild must be called in order to free the
+ * child status structure.
+ *
+ * Parameters:
+ * group - The task group containing the child status.
* pid - The ID of the child to find.
*
* Return Value:
@@ -319,14 +361,17 @@ FAR struct child_status_s *task_findchild(FAR _TCB *tcb, pid_t pid)
*
*****************************************************************************/
-FAR struct child_status_s *task_removechild(FAR _TCB *tcb, pid_t pid)
+FAR struct child_status_s *group_removechild(FAR struct task_group_s *group,
+ pid_t pid)
{
FAR struct child_status_s *curr;
FAR struct child_status_s *prev;
- /* Find the status structure with the matching PID */
+ DEBUGASSERT(group);
- for (prev = NULL, curr = tcb->children;
+ /* Find the status structure with the matching PID */
+
+ for (prev = NULL, curr = group->tg_children;
curr;
prev = curr, curr = curr->flink)
{
@@ -336,7 +381,7 @@ FAR struct child_status_s *task_removechild(FAR _TCB *tcb, pid_t pid)
}
}
- /* Did we find it? If so, remove it from the TCB. */
+ /* Did we find it? If so, remove it from the group. */
if (curr)
{
@@ -348,24 +393,24 @@ FAR struct child_status_s *task_removechild(FAR _TCB *tcb, pid_t pid)
}
else
{
- tcb->children = curr->flink;
+ group->tg_children = curr->flink;
}
curr->flink = NULL;
- task_dumpchildren(tcb, "task_removechild");
+ group_dumpchildren(group, "group_removechild");
}
return curr;
}
/*****************************************************************************
- * Name: task_removechildren
+ * Name: group_removechildren
*
* Description:
- * Remove and free all child structure from the TCB.
+ * Remove and free all child structure from the task group.
*
* Parameters:
- * tcb - The TCB of the parent task to containing the child status.
+ * group - The task group containing the child status.
*
* Return Value:
* None.
@@ -376,21 +421,21 @@ FAR struct child_status_s *task_removechild(FAR _TCB *tcb, pid_t pid)
*
*****************************************************************************/
-void task_removechildren(FAR _TCB *tcb)
+void group_removechildren(FAR struct task_group_s *group)
{
FAR struct child_status_s *curr;
FAR struct child_status_s *next;
/* Remove all child structures for the TCB and return them to the freelist */
- for (curr = tcb->children; curr; curr = next)
+ for (curr = group->tg_children; curr; curr = next)
{
next = curr->flink;
- task_freechild(curr);
+ group_freechild(curr);
}
- tcb->children = NULL;
- task_dumpchildren(tcb, "task_removechildren");
+ group->tg_children = NULL;
+ group_dumpchildren(group, "group_removechildren");
}
#endif /* CONFIG_SCHED_HAVE_PARENT && CONFIG_SCHED_CHILD_STATUS */
diff --git a/nuttx/sched/group_create.c b/nuttx/sched/group_create.c
new file mode 100644
index 000000000..24f6923aa
--- /dev/null
+++ b/nuttx/sched/group_create.c
@@ -0,0 +1,276 @@
+/*****************************************************************************
+ * sched/group_create.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 <sched.h>
+#include <assert.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/kmalloc.h>
+
+#include "group_internal.h"
+#include "env_internal.h"
+
+#ifdef HAVE_TASK_GROUP
+
+/*****************************************************************************
+ * Pre-processor Definitions
+ *****************************************************************************/
+/* Is this worth making a configuration option? */
+
+#define GROUP_INITIAL_MEMBERS 4
+
+/*****************************************************************************
+ * Private Types
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Private Data
+ *****************************************************************************/
+/* This is counter that is used to generate unique task group IDs */
+
+#ifdef HAVE_GROUP_MEMBERS
+static gid_t g_gidcounter;
+#endif
+
+/*****************************************************************************
+ * Public Data
+ *****************************************************************************/
+/* This is the head of a list of all group members */
+
+#ifdef HAVE_GROUP_MEMBERS
+FAR struct task_group_s *g_grouphead;
+#endif
+
+/*****************************************************************************
+ * Private Functions
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Name: group_assigngid
+ *
+ * Description:
+ * Create a unique group ID.
+ *
+ * Parameters:
+ * tcb - The tcb in need of the task group.
+ *
+ * Return Value:
+ * None
+ *
+ * Assumptions:
+ * Called during task creation in a safe context. No special precautions
+ * are required here.
+ *
+ *****************************************************************************/
+
+#ifdef HAVE_GROUP_MEMBERS
+void group_assigngid(FAR struct task_group_s *group)
+{
+ irqstate_t flags;
+ gid_t gid;
+
+ /* Pre-emption should already be enabled, but lets be paranoid careful */
+
+ sched_lock();
+
+ /* Loop until we create a unique ID */
+
+ for (;;)
+ {
+ /* Increment the ID counter. This is global data so be extra paraoid. */
+
+ flags = irqsave();
+ gid = ++g_gidcounter;
+
+ /* Check for overflow */
+
+ if (gid <= 0)
+ {
+ g_gidcounter = 1;
+ irqrestore(flags);
+ }
+ else
+ {
+ /* Does a task group with this ID already exist? */
+
+ irqrestore(flags);
+ if (group_find(gid) == NULL)
+ {
+ /* Now assign this ID to the group and return */
+
+ group->tg_gid = gid;
+ sched_unlock();
+ return;
+ }
+ }
+ }
+}
+#endif /* HAVE_GROUP_MEMBERS */
+
+/*****************************************************************************
+ * Public Functions
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Name: group_allocate
+ *
+ * Description:
+ * 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.
+ *
+ * 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_allocate(FAR _TCB *tcb)
+{
+ int ret;
+
+ 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));
+ if (!tcb->group)
+ {
+ return -ENOMEM;
+ }
+
+ /* Assign the group a unique ID. If g_gidcounter were to wrap before we
+ * finish with task creation, that would be a problem.
+ */
+
+#ifdef HAVE_GROUP_MEMBERS
+ group_assigngid(tcb->group);
+#endif
+
+ /* Duplicate the parent tasks envionment */
+
+ ret = env_dup(tcb->group);
+ if (ret < 0)
+ {
+ kfree(tcb->group);
+ tcb->group = NULL;
+ return ret;
+ }
+
+ return OK;
+}
+
+/*****************************************************************************
+ * 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)
+{
+ FAR struct task_group_s *group;
+#ifdef HAVE_GROUP_MEMBERS
+ irqstate_t flags;
+#endif
+
+ DEBUGASSERT(tcb && tcb->group);
+ group = tcb->group;
+
+#ifdef HAVE_GROUP_MEMBERS
+ /* Allocate space to hold GROUP_INITIAL_MEMBERS members of the group */
+
+ group->tg_members = (FAR pid_t *)kmalloc(GROUP_INITIAL_MEMBERS*sizeof(pid_t));
+ if (!group->tg_members)
+ {
+ free(group);
+ return -ENOMEM;
+ }
+
+ /* 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 */
+
+ /* Add the initialized entry to the list of groups */
+
+ flags = irqsave();
+ group->flink = g_grouphead;
+ g_grouphead = group;
+ irqrestore(flags);
+
+#endif
+
+ group->tg_nmembers = 1; /* Number of members in the group */
+ return OK;
+}
+
+#endif /* HAVE_TASK_GROUP */
diff --git a/nuttx/sched/env_share.c b/nuttx/sched/group_find.c
index 5f37a0219..eb3989223 100644
--- a/nuttx/sched/env_share.c
+++ b/nuttx/sched/group_find.c
@@ -1,7 +1,7 @@
-/****************************************************************************
- * sched/env_share.c
+/*****************************************************************************
+ * sched/group_find.c
*
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
+ * 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
@@ -31,87 +31,95 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
- ****************************************************************************/
+ *****************************************************************************/
-/****************************************************************************
+/*****************************************************************************
* Included Files
- ****************************************************************************/
+ *****************************************************************************/
#include <nuttx/config.h>
-#ifndef CONFIG_DISABLE_ENVIRON
-
#include <sched.h>
+#include <assert.h>
#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/kmalloc.h>
-#include "os_internal.h"
+#include "group_internal.h"
#include "env_internal.h"
-/****************************************************************************
+#ifdef HAVE_TASK_GROUP
+
+/*****************************************************************************
+ * Pre-processor Definitions
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Private Types
+ *****************************************************************************/
+
+/*****************************************************************************
* Private Data
- ****************************************************************************/
+ *****************************************************************************/
-/****************************************************************************
+/*****************************************************************************
+ * Public Data
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Private Functions
+ *****************************************************************************/
+
+/*****************************************************************************
* Public Functions
- ****************************************************************************/
+ *****************************************************************************/
-/****************************************************************************
- * Name: env_share
+/*****************************************************************************
+ * Name: group_find
*
* Description:
- * Increment the reference count on the internal environment structure of
- * a task. This is the action that is performed when a new pthread is
- * created: The new pthread shares the environment with its parent.
+ * Given a group ID, find the group task structure with that ID. IDs are
+ * used instead of pointers to group structures. This is done because a
+ * group can disappear at any time leaving a stale pointer; an ID is cleaner
+ * because if the group disappears, this function will fail gracefully.
*
* Parameters:
- * ptcb The new TCB to receive the shared environment.
+ * gid - The group ID to find.
*
* Return Value:
- * A pointer to a specified TCB's environment structure with an incremented
- * reference count.
+ * On success, a pointer to the group task structure is returned. This
+ * function can fail only if there is no group that corresponds to the
+ * groupd ID.
*
* Assumptions:
- * Not called from an interrupt handler.
+ * Called during when signally tasks in a safe context. No special
+ * precautions should be required here. However, extra care is taken when
+ * accessing the global g_grouphead list.
*
- ****************************************************************************/
+ *****************************************************************************/
-int env_share(FAR _TCB *ptcb)
+#ifdef HAVE_GROUP_MEMBERS
+FAR struct task_group_s *group_find(gid_t gid)
{
- int ret = OK;
- if (!ptcb)
- {
- ret = -EINVAL;
- }
- else
- {
- FAR _TCB *parent = (FAR _TCB*)g_readytorun.head;
- environ_t *envp = parent->envp;
+ FAR struct task_group_s *group;
+ irqstate_t flags;
- /* Pre-emption must be disabled throughout the following because the
- * environment is shared.
- */
+ /* Find the status structure with the matching PID */
- sched_lock();
-
- /* Does the parent task have an environment? */
-
- if (envp)
+ flags = irqsave();
+ for (group = g_grouphead; group; group = group->flink)
+ {
+ if (group->tg_gid == gid)
{
- /* Yes.. increment the reference count on the environment */
-
- envp->ev_crefs++;
+ irqrestore(flags);
+ return group;
}
-
- /* Then share the environment */
-
- ptcb->envp = envp;
- sched_unlock();
}
- return ret;
+ irqrestore(flags);
+ return NULL;
}
+#endif
-#endif /* CONFIG_DISABLE_ENVIRON */
-
-
-
+#endif /* HAVE_TASK_GROUP */
diff --git a/nuttx/sched/sched_setuppthreadfiles.c b/nuttx/sched/group_internal.h
index 648d9273e..ca6aacff7 100644
--- a/nuttx/sched/sched_setuppthreadfiles.c
+++ b/nuttx/sched/group_internal.h
@@ -1,7 +1,7 @@
/****************************************************************************
- * sched_setuppthreadfiles.c
+ * sched/group_internal.h
*
- * Copyright (C) 2007, 2009, 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
@@ -33,76 +33,94 @@
*
****************************************************************************/
+#ifndef __SCHED_GROUP_INERNAL_H
+#define __SCHED_GROUP_INERNAL_H
+
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
+#include <sys/types.h>
+#include <stdbool.h>
+#include <queue.h>
#include <sched.h>
-#include <nuttx/fs/fs.h>
-#include <nuttx/net/net.h>
-#include <nuttx/lib.h>
-
-#include "os_internal.h"
-
-#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
+#include <nuttx/kmalloc.h>
/****************************************************************************
- * Private Functions
+ * Pre-processor Definitions
****************************************************************************/
+/* Any negative GID is invalid. */
+
+#define INVALID_GROUP_ID (pid_t)-1
+#define IS_INVALID_GID(gid) ((int)(gid) < 0)
/****************************************************************************
- * Public Functions
+ * Public Type Definitions
****************************************************************************/
/****************************************************************************
- * Name: sched_setuppthreadfiles
- *
- * Description:
- * Configure a newly allocated TCB so that it will inherit file
- * descriptors and streams from the parent pthread.
- *
- * Parameters:
- * tcb - tcb of the new task.
- *
- * Return Value:
- * OK (if an error were returned, it would need to be a non-negated
- * errno value).
- *
- * Assumptions:
- *
+ * Public Data
****************************************************************************/
+/* This is the head of a list of all group members */
-int sched_setuppthreadfiles(FAR _TCB *tcb)
-{
- FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
+#ifdef HAVE_GROUP_MEMBERS
+extern FAR struct task_group_s *g_grouphead;
+#endif
-#if CONFIG_NFILE_DESCRIPTORS > 0
- /* The child thread inherits the parent file descriptors */
-
- tcb->filelist = rtcb->filelist;
- files_addreflist(tcb->filelist);
-
-#endif /* CONFIG_NFILE_DESCRIPTORS */
-
-#if CONFIG_NSOCKET_DESCRIPTORS > 0
- /* The child thread inherits the parent socket descriptors */
-
- tcb->sockets = rtcb->sockets;
- net_addreflist(tcb->sockets);
-
-#endif /* CONFIG_NSOCKET_DESCRIPTORS */
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+/* Task group data structure management */
+
+#ifdef HAVE_TASK_GROUP
+int group_allocate(FAR _TCB *tcb);
+int group_initialize(FAR _TCB *tcb);
+int group_bind(FAR _TCB *tcb);
+int group_join(FAR _TCB *tcb);
+void group_leave(FAR _TCB *tcb);
+
+#ifdef HAVE_GROUP_MEMBERS
+FAR struct task_group_s *group_find(gid_t gid);
+int group_addmember(FAR struct task_group_s *group, pid_t pid);
+int group_removemember(FAR struct task_group_s *group, pid_t pid);
+#endif
+
+#ifndef CONFIG_DISABLE_SIGNALS
+int group_signal(FAR struct task_group_s *group, FAR siginfo_t *info);
+#endif
+#endif /* HAVE_TASK_GROUP */
+
+/* Parent/child data management */
+
+#ifdef CONFIG_SCHED_HAVE_PARENT
+int task_reparent(pid_t ppid, pid_t chpid);
+
+#ifdef CONFIG_SCHED_CHILD_STATUS
+FAR struct child_status_s *group_allocchild(void);
+void group_freechild(FAR struct child_status_s *status);
+void group_addchild(FAR struct task_group_s *group,
+ FAR struct child_status_s *child);
+FAR struct child_status_s *group_exitchild(FAR struct task_group_s *group);
+FAR struct child_status_s *group_findchild(FAR struct task_group_s *group,
+ pid_t pid);
+FAR struct child_status_s *group_removechild(FAR struct task_group_s *group,
+ pid_t pid);
+void group_removechildren(FAR struct task_group_s *group);
+
+#endif /* CONFIG_SCHED_CHILD_STATUS */
+#endif /* CONFIG_SCHED_HAVE_PARENT */
+
+/* Group data resource configuration */
+#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
+int group_setupidlefiles(FAR _TCB *tcb);
+int group_setuptaskfiles(FAR _TCB *tcb);
#if CONFIG_NFILE_STREAMS > 0
- /* The child thread inherits the parent streams */
-
- tcb->streams = rtcb->streams;
- lib_addreflist(tcb->streams);
-
-#endif /* CONFIG_NFILE_STREAMS */
- return OK;
-}
+int group_setupstreams(FAR _TCB *tcb);
+#endif
+#endif
-#endif /* CONFIG_NFILE_DESCRIPTORS || CONFIG_NSOCKET_DESCRIPTORS */
+#endif /* __SCHED_GROUP_INERNAL_H */
diff --git a/nuttx/sched/group_join.c b/nuttx/sched/group_join.c
new file mode 100644
index 000000000..70319b3a1
--- /dev/null
+++ b/nuttx/sched/group_join.c
@@ -0,0 +1,227 @@
+/*****************************************************************************
+ * sched/group_join.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 <sched.h>
+#include <assert.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/kmalloc.h>
+
+#include "group_internal.h"
+#include "env_internal.h"
+
+#ifdef HAVE_TASK_GROUP
+
+/*****************************************************************************
+ * Pre-processor Definitions
+ *****************************************************************************/
+/* Is this worth making a configuration option? */
+
+#define GROUP_REALLOC_MEMBERS 4
+
+/*****************************************************************************
+ * Private Types
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Private Data
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Private Functions
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Public Functions
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Name: group_bind
+ *
+ * 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_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 */
+
+ tcb->group = ptcb->group;
+ 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)
+{
+ FAR struct task_group_s *group;
+#ifdef HAVE_GROUP_MEMBERS
+ int ret;
+#endif
+
+ DEBUGASSERT(tcb && tcb->group &&
+ tcb->group->tg_nmembers < UINT8_MAX);
+
+ /* Get the group from the TCB */
+
+ group = tcb->group;
+
+#ifdef HAVE_GROUP_MEMBERS
+ /* Add the member to the group */
+
+ ret = group_addmember(group, tcb->pid);
+ if (ret < 0)
+ {
+ return ret;
+ }
+#endif
+
+ group->tg_nmembers++;
+ return OK;
+}
+
+/*****************************************************************************
+ * Name: group_addmember
+ *
+ * Description:
+ * Add a new member to a group.
+ *
+ * Parameters:
+ * group - The task group to add the new member
+ * pid - The new member
+ *
+ * Return Value:
+ * 0 (OK) on success; a negated errno value on failure.
+ *
+ * Assumptions:
+ * Called during thread creation and during reparenting in a safe context.
+ * No special precautions are required here.
+ *
+ *****************************************************************************/
+
+#ifdef HAVE_GROUP_MEMBERS
+int group_addmember(FAR struct task_group_s *group, pid_t pid)
+{
+ DEBUGASSERT(group && group->tg_nmembers < UINT8_MAX);
+
+ /* 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] = pid;
+ return OK;
+}
+#endif /* HAVE_GROUP_MEMBERS */
+
+#endif /* HAVE_TASK_GROUP */
diff --git a/nuttx/sched/group_leave.c b/nuttx/sched/group_leave.c
new file mode 100644
index 000000000..4dec30633
--- /dev/null
+++ b/nuttx/sched/group_leave.c
@@ -0,0 +1,366 @@
+/*****************************************************************************
+ * sched/group_leave.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 <sched.h>
+#include <assert.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/fs/fs.h>
+#include <nuttx/net/net.h>
+#include <nuttx/lib.h>
+
+#include "group_internal.h"
+#include "env_internal.h"
+
+#ifdef HAVE_TASK_GROUP
+
+/*****************************************************************************
+ * Pre-processor Definitions
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Private Types
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Private Data
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Private Functions
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Name: group_remove
+ *
+ * Description:
+ * Remove a group from the list of groups.
+ *
+ * Parameters:
+ * group - The group to be removed.
+ *
+ * Return Value:
+ * None.
+ *
+ * Assumptions:
+ * Called during task deletion in a safe context. No special precautions
+ * are required here.
+ *
+ *****************************************************************************/
+
+#ifdef HAVE_GROUP_MEMBERS
+void group_remove(FAR struct task_group_s *group)
+{
+ FAR struct task_group_s *curr;
+ FAR struct task_group_s *prev;
+ irqstate_t flags;
+
+ /* Let's be especially careful while access the global task group list.
+ * This is probably un-necessary.
+ */
+
+ flags = irqsave();
+
+ /* Find the task group structure */
+
+ for (prev = NULL, curr = g_grouphead;
+ curr && curr != group;
+ prev = curr, curr = curr->flink);
+
+ /* Did we find it? If so, remove it from the list. */
+
+ if (curr)
+ {
+ /* Do we remove it from mid-list? Or from the head of the list? */
+
+ if (prev)
+ {
+ prev->flink = curr->flink;
+ }
+ else
+ {
+ g_grouphead = curr->flink;
+ }
+
+ curr->flink = NULL;
+ }
+
+ irqrestore(flags);
+}
+#endif
+
+/*****************************************************************************
+ * Name: group_release
+ *
+ * Description:
+ * Release group resources after the last member has left the group.
+ *
+ * Parameters:
+ * group - The group to be removed.
+ *
+ * Return Value:
+ * None.
+ *
+ * Assumptions:
+ * Called during task deletion in a safe context. No special precautions
+ * are required here.
+ *
+ *****************************************************************************/
+
+static inline void group_release(FAR struct task_group_s *group)
+{
+ /* Free all un-reaped child exit status */
+
+#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS)
+ group_removechildren(group);
+#endif
+
+ /* Free all file-related resources now. We really need to close files as
+ * soon as possible while we still have a functioning task.
+ */
+
+#if CONFIG_NFILE_DESCRIPTORS > 0
+ /* Free resources held by the file descriptor list */
+
+ files_releaselist(&group->tg_filelist);
+
+#if CONFIG_NFILE_STREAMS > 0
+ /* Free resource held by the stream list */
+
+ lib_releaselist(&group->tg_streamlist);
+
+#endif /* CONFIG_NFILE_STREAMS */
+#endif /* CONFIG_NFILE_DESCRIPTORS */
+
+#if CONFIG_NSOCKET_DESCRIPTORS > 0
+ /* Free resource held by the socket list */
+
+ net_releaselist(&group->tg_socketlist);
+#endif /* CONFIG_NSOCKET_DESCRIPTORS */
+
+ /* Release all shared environment variables */
+
+#ifndef CONFIG_DISABLE_ENVIRON
+ env_release(group);
+#endif
+
+#ifdef HAVE_GROUP_MEMBERS
+ /* Remove the group from the list of groups */
+
+ group_remove(group);
+
+ /* Release the members array */
+
+ if (group->tg_members)
+ {
+ sched_free(group->tg_members);
+ group->tg_members = NULL;
+ }
+#endif
+
+ /* Release the group container itself */
+
+ sched_free(group);
+}
+
+/*****************************************************************************
+ * Public Functions
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Name: group_leave
+ *
+ * Description:
+ * Release a reference on a group. This function is called when a task or
+ * thread exits. It decrements the reference count on the group. If the
+ * reference count decrements to zero, then it frees the group and all of
+ * resources contained in the group.
+ *
+ * Parameters:
+ * tcb - The TCB of the task that is exiting.
+ *
+ * Return Value:
+ * None.
+ *
+ * Assumptions:
+ * Called during task deletion in a safe context. No special precautions
+ * are required here.
+ *
+ *****************************************************************************/
+
+#ifdef HAVE_GROUP_MEMBERS
+void group_leave(FAR _TCB *tcb)
+{
+ FAR struct task_group_s *group;
+
+ DEBUGASSERT(tcb);
+
+ /* Make sure that we have a group */
+
+ group = tcb->group;
+ if (group)
+ {
+ /* Remove the member from group */
+
+ int ret = group_removemember(group, tcb->pid);
+ DEBUGASSERT(ret >= 0);
+
+ /* Is the group now empty? */
+
+ if (ret == 0)
+ {
+ /* Release all of the resource held by the task group */
+
+ group_release(group);
+ }
+
+ /* In any event, we can detach the group from the TCB so that we won't
+ * do this again.
+ */
+
+ tcb->group = NULL;
+ }
+}
+
+#else /* HAVE_GROUP_MEMBERS */
+
+void group_leave(FAR _TCB *tcb)
+{
+ FAR struct task_group_s *group;
+
+ DEBUGASSERT(tcb);
+
+ /* Make sure that we have a group */
+
+ group = tcb->group;
+ if (group)
+ {
+ /* Yes, we have a group.. 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
+ {
+ /* Release all of the resource held by the task group */
+
+ group_release(group);
+ }
+
+ /* In any event, we can detach the group from the TCB so we won't do
+ * this again.
+ */
+
+ tcb->group = NULL;
+ }
+}
+
+#endif /* HAVE_GROUP_MEMBERS */
+
+/*****************************************************************************
+ * Name: group_removemember
+ *
+ * Description:
+ * Remove a member from a group.
+ *
+ * Parameters:
+ * group - The group from which to remove the member.
+ * pid - The member to be removed.
+ *
+ * Return Value:
+ * On success, returns the number of members remaining in the group (>=0).
+ * Can fail only if the member is not found in the group. On failure,
+ * returns -ENOENT
+ *
+ * Assumptions:
+ * Called during task deletion and also from the reparenting logic, both
+ * in a safe context. No special precautions are required here.
+ *
+ *****************************************************************************/
+
+#ifdef HAVE_GROUP_MEMBERS
+int group_removemember(FAR struct task_group_s *group, pid_t pid)
+{
+ int i;
+
+ DEBUGASSERT(group);
+
+ /* Find the member in the array of members and remove it */
+
+ for (i = 0; i < group->tg_nmembers; i++)
+ {
+ /* Does this member have the matching pid */
+
+ if (group->tg_members[i] == 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. */
+
+ if (i < group->tg_nmembers)
+ {
+ /* Remove the member from the array of members */
+
+ group->tg_members[i] = group->tg_members[group->tg_nmembers - 1];
+ group->tg_nmembers--;
+ return group->tg_nmembers;
+ }
+
+ return -ENOENT;
+}
+#endif /* HAVE_GROUP_MEMBERS */
+
+#endif /* HAVE_TASK_GROUP */
diff --git a/nuttx/sched/sched_setupidlefiles.c b/nuttx/sched/group_setupidlefiles.c
index ae814e1a6..ceb9f3e2c 100644
--- a/nuttx/sched/sched_setupidlefiles.c
+++ b/nuttx/sched/group_setupidlefiles.c
@@ -1,7 +1,7 @@
/****************************************************************************
- * sched/sched_setupidlefiles.c
+ * sched/group_setupidlefiles.c
*
- * Copyright (C) 2007-2010, 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2010, 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -50,6 +50,7 @@
#include <nuttx/net/net.h>
#include "os_internal.h"
+#include "group_internal.h"
#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
@@ -62,7 +63,7 @@
****************************************************************************/
/****************************************************************************
- * Name: sched_setupidlefiles
+ * Name: group_setupidlefiles
*
* Description:
* Configure the idle thread's TCB.
@@ -77,30 +78,29 @@
*
****************************************************************************/
-int sched_setupidlefiles(FAR _TCB *tcb)
+int group_setupidlefiles(FAR _TCB *tcb)
{
+#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0
+ FAR struct task_group_s *group = tcb->group;
+#endif
#if CONFIG_NFILE_DESCRIPTORS > 0 && defined(CONFIG_DEV_CONSOLE)
int fd;
#endif
- /* Allocate file descriptors for the TCB */
+#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0
+ DEBUGASSERT(group);
+#endif
#if CONFIG_NFILE_DESCRIPTORS > 0
- tcb->filelist = files_alloclist();
- if (!tcb->filelist)
- {
- return -ENOMEM;
- }
+ /* Initialize file descriptors for the TCB */
+
+ files_initlist(&group->tg_filelist);
#endif
+#if CONFIG_NSOCKET_DESCRIPTORS > 0
/* Allocate socket descriptors for the TCB */
-#if CONFIG_NSOCKET_DESCRIPTORS > 0
- tcb->sockets = net_alloclist();
- if (!tcb->sockets)
- {
- return -ENOMEM;
- }
+ net_initlist(&group->tg_socketlist);
#endif
/* Open stdin, dup to get stdout and stderr. This should always
@@ -139,7 +139,7 @@ int sched_setupidlefiles(FAR _TCB *tcb)
/* Allocate file/socket streams for the TCB */
#if CONFIG_NFILE_STREAMS > 0
- return sched_setupstreams(tcb);
+ return group_setupstreams(tcb);
#else
return OK;
#endif
diff --git a/nuttx/sched/sched_setupstreams.c b/nuttx/sched/group_setupstreams.c
index 22895b047..08399ae41 100644
--- a/nuttx/sched/sched_setupstreams.c
+++ b/nuttx/sched/group_setupstreams.c
@@ -1,7 +1,7 @@
/****************************************************************************
- * sched_setupstreams.c
+ * group_setupstreams.c
*
- * Copyright (C) 2007-2008, 2010-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2008, 2010-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -46,6 +46,8 @@
#include <nuttx/net/net.h>
#include <nuttx/lib.h>
+#include "group_internal.h"
+
/* Make sure that there are file or socket descriptors in the system and
* that some number of streams have been configured.
*/
@@ -62,7 +64,7 @@
****************************************************************************/
/****************************************************************************
- * Name: sched_setupstreams
+ * Name: group_setupstreams
*
* Description:
* Setup streams data structures that may be used for standard C buffered
@@ -70,26 +72,25 @@
*
****************************************************************************/
-int sched_setupstreams(FAR _TCB *tcb)
+int group_setupstreams(FAR _TCB *tcb)
{
- /* Allocate file streams for the TCB */
-
- tcb->streams = lib_alloclist();
- if (tcb->streams)
- {
- /* fdopen to get the stdin, stdout and stderr streams.
- * The following logic depends on the fact that the library
- * layer will allocate FILEs in order.
- *
- * fd = 0 is stdin (read-only)
- * fd = 1 is stdout (write-only, append)
- * fd = 2 is stderr (write-only, append)
- */
-
- (void)fs_fdopen(0, O_RDONLY, tcb);
- (void)fs_fdopen(1, O_WROK|O_CREAT, tcb);
- (void)fs_fdopen(2, O_WROK|O_CREAT, tcb);
- }
+ DEBUGASSERT(tcb && tcb->group);
+
+ /* Initialize file streams for the task group */
+
+ lib_streaminit(&tcb->group->tg_streamlist);
+
+ /* fdopen to get the stdin, stdout and stderr streams. The following logic
+ * depends on the fact that the library layer will allocate FILEs in order.
+ *
+ * fd = 0 is stdin (read-only)
+ * fd = 1 is stdout (write-only, append)
+ * fd = 2 is stderr (write-only, append)
+ */
+
+ (void)fs_fdopen(0, O_RDONLY, tcb);
+ (void)fs_fdopen(1, O_WROK|O_CREAT, tcb);
+ (void)fs_fdopen(2, O_WROK|O_CREAT, tcb);
return OK;
}
diff --git a/nuttx/sched/sched_setuptaskfiles.c b/nuttx/sched/group_setuptaskfiles.c
index d01b8d4cd..e2e7d4634 100644
--- a/nuttx/sched/sched_setuptaskfiles.c
+++ b/nuttx/sched/group_setuptaskfiles.c
@@ -1,7 +1,7 @@
/****************************************************************************
- * sched/sched_setuptaskfiles.c
+ * sched/group_setuptaskfiles.c
*
- * Copyright (C) 2007-2008, 2010, 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2008, 2010, 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -46,6 +46,7 @@
#include <nuttx/net/net.h>
#include "os_internal.h"
+#include "group_internal.h"
#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
@@ -93,34 +94,33 @@ static inline void sched_dupfiles(FAR _TCB *tcb)
FAR struct file *child;
int i;
+ DEBUGASSERT(tcb && tcb->group && rtcb->group);
+
/* Duplicate the file descriptors. This will be either all of the
* file descriptors or just the first three (stdin, stdout, and stderr)
* if CONFIG_FDCLONE_STDIO is defined. NFSDS_TOCLONE is set
* accordingly above.
*/
- if (rtcb->filelist)
- {
- /* Get pointers to the parent and child task file lists */
+ /* Get pointers to the parent and child task file lists */
- parent = rtcb->filelist->fl_files;
- child = tcb->filelist->fl_files;
+ parent = rtcb->group->tg_filelist.fl_files;
+ child = tcb->group->tg_filelist.fl_files;
- /* Check each file in the parent file list */
+ /* Check each file in the parent file list */
- for (i = 0; i < NFDS_TOCLONE; i++)
- {
- /* Check if this file is opened by the parent. We can tell if
- * if the file is open because it contain a reference to a non-NULL
- * i-node structure.
- */
+ for (i = 0; i < NFDS_TOCLONE; i++)
+ {
+ /* Check if this file is opened by the parent. We can tell if
+ * if the file is open because it contain a reference to a non-NULL
+ * i-node structure.
+ */
- if (parent[i].f_inode)
- {
- /* Yes... duplicate it for the child */
+ if (parent[i].f_inode)
+ {
+ /* Yes... duplicate it for the child */
- (void)files_dup(&parent[i], &child[i]);
- }
+ (void)files_dup(&parent[i], &child[i]);
}
}
}
@@ -152,32 +152,31 @@ static inline void sched_dupsockets(FAR _TCB *tcb)
FAR struct socket *child;
int i;
- /* Duplicate the socket descriptors of all sockets opened by the parent
- * task.
- */
+ /* Duplicate the socket descriptors of all sockets opened by the parent
+ * task.
+ */
- if (rtcb->sockets)
- {
- /* Get pointers to the parent and child task socket lists */
+ DEBUGASSERT(tcb && tcb->group && rtcb->group);
- parent = rtcb->sockets->sl_sockets;
- child = tcb->sockets->sl_sockets;
+ /* Get pointers to the parent and child task socket lists */
- /* Check each socket in the parent socket list */
+ parent = rtcb->group->tg_socketlist.sl_sockets;
+ child = tcb->group->tg_socketlist.sl_sockets;
- for (i = 0; i < CONFIG_NSOCKET_DESCRIPTORS; i++)
- {
- /* Check if this parent socket is allocated. We can tell if the
- * socket is allocated because it will have a positive, non-zero
- * reference count.
- */
+ /* Check each socket in the parent socket list */
- if (parent[i].s_crefs > 0)
- {
- /* Yes... duplicate it for the child */
+ for (i = 0; i < CONFIG_NSOCKET_DESCRIPTORS; i++)
+ {
+ /* Check if this parent socket is allocated. We can tell if the
+ * socket is allocated because it will have a positive, non-zero
+ * reference count.
+ */
+
+ if (parent[i].s_crefs > 0)
+ {
+ /* Yes... duplicate it for the child */
- (void)net_clone(&parent[i], &child[i]);
- }
+ (void)net_clone(&parent[i], &child[i]);
}
}
}
@@ -190,7 +189,7 @@ static inline void sched_dupsockets(FAR _TCB *tcb)
****************************************************************************/
/****************************************************************************
- * Name: sched_setuptaskfiles
+ * Name: group_setuptaskfiles
*
* Description:
* Configure a newly allocated TCB so that it will inherit
@@ -207,26 +206,24 @@ static inline void sched_dupsockets(FAR _TCB *tcb)
*
****************************************************************************/
-int sched_setuptaskfiles(FAR _TCB *tcb)
+int group_setuptaskfiles(FAR _TCB *tcb)
{
- /* Allocate file descriptors for the TCB */
+#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
+ FAR struct task_group_s *group = tcb->group;
+
+ DEBUGASSERT(group);
+#endif
#if CONFIG_NFILE_DESCRIPTORS > 0
- tcb->filelist = files_alloclist();
- if (!tcb->filelist)
- {
- return -ENOMEM;
- }
+ /* Initialize file descriptors for the TCB */
+
+ files_initlist(&group->tg_filelist);
#endif
+#if CONFIG_NSOCKET_DESCRIPTORS > 0
/* Allocate socket descriptors for the TCB */
-#if CONFIG_NSOCKET_DESCRIPTORS > 0
- tcb->sockets = net_alloclist();
- if (!tcb->sockets)
- {
- return -ENOMEM;
- }
+ net_initlist(&group->tg_socketlist);
#endif
/* Duplicate the parent task's file descriptors */
@@ -240,7 +237,7 @@ int sched_setuptaskfiles(FAR _TCB *tcb)
/* Allocate file/socket streams for the new TCB */
#if CONFIG_NFILE_STREAMS > 0
- return sched_setupstreams(tcb);
+ return group_setupstreams(tcb);
#else
return OK;
#endif
diff --git a/nuttx/sched/group_signal.c b/nuttx/sched/group_signal.c
new file mode 100644
index 000000000..009ab7a55
--- /dev/null
+++ b/nuttx/sched/group_signal.c
@@ -0,0 +1,163 @@
+/*****************************************************************************
+ * sched/group_signal.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 <sched.h>
+#include <assert.h>
+#include <signal.h>
+#include <errno.h>
+#include <debug.h>
+
+#include "os_internal.h"
+#include "group_internal.h"
+#include "sig_internal.h"
+
+#if defined(HAVE_TASK_GROUP) && !defined(CONFIG_DISABLE_SIGNALS)
+
+/*****************************************************************************
+ * Pre-processor Definitions
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Private Types
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Private Data
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Private Functions
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Public Functions
+ *****************************************************************************/
+
+/*****************************************************************************
+ * Name: group_signal
+ *
+ * Description:
+ * Send a signal to every member of the group.
+ *
+ * Parameters:
+ * group - The task group that needs to be signalled.
+ *
+ * Return Value:
+ * 0 (OK) on success; a negated errno value on failure.
+ *
+ * Assumptions:
+ * Called during task terminatino in a safe context. No special precautions
+ * are required here.
+ *
+ *****************************************************************************/
+
+int group_signal(FAR struct task_group_s *group, FAR siginfo_t *info)
+{
+#ifdef HAVE_GROUP_MEMBERS
+ FAR _TCB *gtcb;
+ int i;
+
+ DEBUGASSERT(group && info);
+
+ /* Make sure that pre-emption is disabled to that we signal all of teh
+ * members of the group before any of them actually run.
+ */
+
+ sched_lock();
+
+ /* Send the signal to each member of the group */
+
+ for (i = 0; i < group->tg_nmembers; i++)
+ {
+ gtcb = sched_gettcb(group->tg_members[i]);
+ DEBUGASSERT(gtcb);
+ if (gtcb)
+ {
+ /* Use the sig_received interface so that it does not muck with
+ * the siginfo_t.
+ */
+
+#ifdef CONFIG_DEBUG
+ int ret = sig_received(gtcb, info);
+ DEBUGASSERT(ret == 0);
+#else
+ (void)sig_received(gtcb, info);
+#endif
+ }
+ }
+
+ /* Re-enable pre-emption an return success */
+
+ sched_unlock();
+ return OK;
+#else
+ return -ENOSYS;
+#endif
+}
+
+/*****************************************************************************
+ * Name: group_signalmember
+ *
+ * Description:
+ * Send a signal to every member of the group to which task belongs.
+ *
+ * Parameters:
+ * tcb - The tcb of one task in the task group that needs to be signalled.
+ *
+ * Return Value:
+ * 0 (OK) on success; a negated errno value on failure.
+ *
+ * Assumptions:
+ * Called during task terminatino in a safe context. No special precautions
+ * are required here.
+ *
+ *****************************************************************************/
+
+int group_signalmember(FAR _TCB *tcb, FAR siginfo_t *info)
+{
+#ifdef HAVE_GROUP_MEMBERS
+ DEBUGASSERT(tcb);
+ return group_signal(tcb->group, info);
+#else
+ return sig_received(tcb, info);
+#endif
+}
+#endif /* HAVE_TASK_GROUP && !CONFIG_DISABLE_SIGNALS */
diff --git a/nuttx/sched/mq_sndinternal.c b/nuttx/sched/mq_sndinternal.c
index 51f898875..f16f7de1a 100644
--- a/nuttx/sched/mq_sndinternal.c
+++ b/nuttx/sched/mq_sndinternal.c
@@ -124,7 +124,7 @@ int mq_verifysend(mqd_t mqdes, const void *msg, size_t msglen, int prio)
return ERROR;
}
- if (msglen < 0 || msglen > (size_t)mqdes->msgq->maxmsgsize)
+ if (msglen > (size_t)mqdes->msgq->maxmsgsize)
{
set_errno(EMSGSIZE);
return ERROR;
diff --git a/nuttx/sched/os_internal.h b/nuttx/sched/os_internal.h
index 7d5095bad..262a40ccc 100644
--- a/nuttx/sched/os_internal.h
+++ b/nuttx/sched/os_internal.h
@@ -99,15 +99,6 @@ enum os_crash_codes_e
#define MAX_TASKS_MASK (CONFIG_MAX_TASKS-1)
#define PIDHASH(pid) ((pid) & MAX_TASKS_MASK)
-/* Stubs used when there are no file descriptors */
-
-#if CONFIG_NFILE_DESCRIPTORS <= 0 && CONFIG_NSOCKET_DESCRIPTORS <= 0
-# define sched_setupidlefiles(t) (OK)
-# define sched_setuptaskfiles(t) (OK)
-# define sched_setuppthreadfiles(t) (OK)
-# define sched_releasefiles(t) (OK)
-#endif
-
/* One processor family supported by NuttX has a single, fixed hardware stack.
* That is the 8051 family. So for that family only, there is a variant form
* of kernel_thread() that does not take a stack size parameter. The following
@@ -262,24 +253,16 @@ extern const tasklist_t g_tasklisttable[NUM_TASK_STATES];
****************************************************************************/
int os_bringup(void);
+#ifdef CONFIG_SCHED_CHILD_STATUS
+void weak_function task_initialize(void);
+#endif
void task_start(void);
int task_schedsetup(FAR _TCB *tcb, int priority, start_t start,
main_t main, uint8_t ttype);
int task_argsetup(FAR _TCB *tcb, FAR const char *name, FAR const char *argv[]);
void task_exithook(FAR _TCB *tcb, int status);
int task_deletecurrent(void);
-#ifdef CONFIG_SCHED_HAVE_PARENT
-#ifdef CONFIG_SCHED_CHILD_STATUS
-void weak_function task_initialize(void);
-FAR struct child_status_s *task_allocchild(void);
-void task_freechild(FAR struct child_status_s *status);
-void task_addchild(FAR _TCB *tcb, FAR struct child_status_s *child);
-FAR struct child_status_s *task_findchild(FAR _TCB *tcb, pid_t pid);
-FAR struct child_status_s *task_removechild(FAR _TCB *tcb, pid_t pid);
-void task_removechildren(FAR _TCB *tcb);
-#endif
-int task_reparent(pid_t ppid, pid_t chpid);
-#endif
+
#ifndef CONFIG_CUSTOM_STACK
int kernel_thread(FAR const char *name, int priority, int stack_size,
main_t entry, FAR const char *argv[]);
@@ -302,16 +285,6 @@ int sched_reprioritize(FAR _TCB *tcb, int sched_priority);
FAR _TCB *sched_gettcb(pid_t pid);
bool sched_verifytcb(FAR _TCB *tcb);
-#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
-int sched_setupidlefiles(FAR _TCB *tcb);
-int sched_setuptaskfiles(FAR _TCB *tcb);
-int sched_setuppthreadfiles(FAR _TCB *tcb);
-#if CONFIG_NFILE_STREAMS > 0
-int sched_setupstreams(FAR _TCB *tcb);
-#endif
-int sched_releasefiles(FAR _TCB *tcb);
-#endif
-
int sched_releasetcb(FAR _TCB *tcb);
void sched_garbagecollection(void);
diff --git a/nuttx/sched/os_start.c b/nuttx/sched/os_start.c
index a6d4e83b9..c60edc495 100644
--- a/nuttx/sched/os_start.c
+++ b/nuttx/sched/os_start.c
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/os_start.c
*
- * 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
@@ -63,6 +63,9 @@
#include "clock_internal.h"
#include "timer_internal.h"
#include "irq_internal.h"
+#ifdef HAVE_TASK_GROUP
+#include "group_internal.h"
+#endif
/****************************************************************************
* Pre-processor Definitions
@@ -286,7 +289,6 @@ void os_start(void)
/* Initialize the processor-specific portion of the TCB */
- g_idletcb.flags = (TCB_FLAG_TTYPE_KERNEL | TCB_FLAG_NOCLDWAIT);
up_initial_state(&g_idletcb);
/* Initialize the semaphore facility(if in link). This has to be done
@@ -325,6 +327,12 @@ void os_start(void)
}
#endif
+ /* Allocate the IDLE group and suppress child status. */
+
+#ifdef HAVE_TASK_GROUP
+ (void)group_allocate(&g_idletcb);
+#endif
+
/* Initialize the interrupt handling subsystem (if included) */
#ifdef CONFIG_HAVE_WEAKFUNCTIONS
@@ -441,7 +449,16 @@ void os_start(void)
* inherited by all of the threads created by the IDLE task.
*/
- (void)sched_setupidlefiles(&g_idletcb);
+ (void)group_setupidlefiles(&g_idletcb);
+
+ /* Complete initialization of the IDLE group. Suppress retention
+ * of child status in the IDLE group.
+ */
+
+#ifdef HAVE_TASK_GROUP
+ (void)group_initialize(&g_idletcb);
+ g_idletcb.group->tg_flags = GROUP_FLAG_NOCLDWAIT;
+#endif
/* Create initial tasks and bring-up the system */
diff --git a/nuttx/sched/pthread_create.c b/nuttx/sched/pthread_create.c
index f4d0d8fdf..48a0788a6 100644
--- a/nuttx/sched/pthread_create.c
+++ b/nuttx/sched/pthread_create.c
@@ -53,8 +53,8 @@
#include <nuttx/arch.h>
#include "os_internal.h"
+#include "group_internal.h"
#include "clock_internal.h"
-#include "env_internal.h"
#include "pthread_internal.h"
/****************************************************************************
@@ -246,12 +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 */
@@ -268,6 +269,19 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
return ENOMEM;
}
+ /* Bind the parent's group to the new TCB (we have not yet joined the
+ * group).
+ */
+
+#ifdef HAVE_TASK_GROUP
+ 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
* created throught the nuttx/binfmt loaders may have an address
* environment.
@@ -277,31 +291,18 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
ret = up_addrenv_share((FAR const _TCB *)g_readytorun.head, ptcb);
if (ret < 0)
{
- sched_releasetcb(ptcb);
- return -ret;
+ errcode = -ret;
+ goto errout_with_tcb;
}
#endif
- /* Associate file descriptors with the new task */
-
- ret = sched_setuppthreadfiles(ptcb);
- if (ret != OK)
- {
- sched_releasetcb(ptcb);
- return ret;
- }
-
- /* Share the parent's envionment */
-
- (void)env_share(ptcb);
-
/* Allocate a detachable structure to support pthread_join logic */
pjoin = (FAR join_t*)kzalloc(sizeof(join_t));
if (!pjoin)
{
- sched_releasetcb(ptcb);
- return ENOMEM;
+ errcode = ENOMEM;
+ goto errout_with_tcb;
}
/* Allocate the stack for the TCB */
@@ -309,9 +310,8 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
ret = up_create_stack(ptcb, attr->stacksize);
if (ret != OK)
{
- sched_releasetcb(ptcb);
- sched_free(pjoin);
- return ENOMEM;
+ errcode = ENOMEM;
+ goto errout_with_join;
}
/* Should we use the priority and scheduler specified in the
@@ -360,9 +360,8 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
TCB_FLAG_TTYPE_PTHREAD);
if (ret != OK)
{
- sched_releasetcb(ptcb);
- sched_free(pjoin);
- return EBUSY;
+ errcode = EBUSY;
+ goto errout_with_join;
}
/* Configure the TCB for a pthread receiving on parameter
@@ -371,6 +370,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;
@@ -440,10 +450,18 @@ int pthread_create(FAR pthread_t *thread, FAR pthread_attr_t *attr,
dq_rem((FAR dq_entry_t*)ptcb, (dq_queue_t*)&g_inactivetasks);
(void)sem_destroy(&pjoin->data_sem);
(void)sem_destroy(&pjoin->exit_sem);
- sched_releasetcb(ptcb);
- sched_free(pjoin);
- ret = EIO;
+
+ errcode = EIO;
+ goto errout_with_join;
}
return ret;
+
+errout_with_join:
+ sched_free(pjoin);
+ ptcb->joininfo = NULL;
+
+errout_with_tcb:
+ sched_releasetcb(ptcb);
+ return errcode;
}
diff --git a/nuttx/sched/pthread_join.c b/nuttx/sched/pthread_join.c
index 6a02af352..d3f648dc7 100644
--- a/nuttx/sched/pthread_join.c
+++ b/nuttx/sched/pthread_join.c
@@ -123,7 +123,7 @@ int pthread_join(pthread_t thread, FAR pthread_addr_t *pexit_value)
* This can fail for one of three reasons: (1) There is no
* thread associated with 'thread,' (2) the thread is a task
* and does not have join information, or (3) the thread
- * was detached and has exitted.
+ * was detached and has exited.
*/
pjoin = pthread_findjoininfo((pid_t)thread);
diff --git a/nuttx/sched/sched_getfiles.c b/nuttx/sched/sched_getfiles.c
index 256b4cb6b..17ca2bbf6 100644
--- a/nuttx/sched/sched_getfiles.c
+++ b/nuttx/sched/sched_getfiles.c
@@ -1,7 +1,7 @@
/************************************************************************
* sched/sched_getfiles.c
*
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -70,7 +70,10 @@
FAR struct filelist *sched_getfiles(void)
{
FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
- return rtcb->filelist;
+ FAR struct task_group_s *group = rtcb->group;
+
+ DEBUGASSERT(group);
+ return &group->tg_filelist;
}
#endif /* CONFIG_NFILE_DESCRIPTORS */
diff --git a/nuttx/sched/sched_getsockets.c b/nuttx/sched/sched_getsockets.c
index cd499420f..ea988d6ff 100644
--- a/nuttx/sched/sched_getsockets.c
+++ b/nuttx/sched/sched_getsockets.c
@@ -1,7 +1,7 @@
/************************************************************************
* sched/sched_getsockets.c
*
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -71,7 +71,10 @@
FAR struct socketlist *sched_getsockets(void)
{
FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
- return rtcb->sockets;
+ FAR struct task_group_s *group = rtcb->group;
+
+ DEBUGASSERT(group);
+ return &group->tg_socketlist;
}
#endif /* CONFIG_NSOCKET_DESCRIPTORS */
diff --git a/nuttx/sched/sched_getstreams.c b/nuttx/sched/sched_getstreams.c
index f7c21ab4c..dab406e66 100644
--- a/nuttx/sched/sched_getstreams.c
+++ b/nuttx/sched/sched_getstreams.c
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/sched_getstreams.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -70,7 +70,10 @@
FAR struct streamlist *sched_getstreams(void)
{
FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
- return rtcb->streams;
+ FAR struct task_group_s *group = rtcb->group;
+
+ DEBUGASSERT(group);
+ return &group->tg_streamlist;
}
#endif /* CONFIG_NFILE_DESCRIPTORS && CONFIG_NFILE_STREAMS */
diff --git a/nuttx/sched/sched_releasetcb.c b/nuttx/sched/sched_releasetcb.c
index 0557c829b..02f7170c2 100644
--- a/nuttx/sched/sched_releasetcb.c
+++ b/nuttx/sched/sched_releasetcb.c
@@ -1,7 +1,7 @@
/************************************************************************
* sched/sched_releasetcb.c
*
- * Copyright (C) 2007, 2009, 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -45,8 +45,8 @@
#include <nuttx/arch.h>
#include "os_internal.h"
+#include "group_internal.h"
#include "timer_internal.h"
-#include "env_internal.h"
/************************************************************************
* Private Functions
@@ -163,20 +163,17 @@ int sched_releasetcb(FAR _TCB *tcb)
}
}
- /* Release any allocated file structures */
-
- ret = sched_releasefiles(tcb);
-
- /* Release environment variables */
-
- (void)env_release(tcb);
-
/* Release this thread's reference to the address environment */
#ifdef CONFIG_ADDRENV
ret = up_addrenv_release(tcb);
#endif
+ /* Leave the group (if we did not already leady in task_exithook.c) */
+
+#ifdef HAVE_TASK_GROUP
+ group_leave(tcb);
+#endif
/* And, finally, release the TCB itself */
sched_free(tcb);
diff --git a/nuttx/sched/sched_waitid.c b/nuttx/sched/sched_waitid.c
index 37ee26ce0..9c24189c4 100644
--- a/nuttx/sched/sched_waitid.c
+++ b/nuttx/sched/sched_waitid.c
@@ -46,6 +46,7 @@
#include <nuttx/sched.h>
#include "os_internal.h"
+#include "group_internal.h"
#if defined(CONFIG_SCHED_WAITPID) && defined(CONFIG_SCHED_HAVE_PARENT)
@@ -54,6 +55,36 @@
*****************************************************************************/
/*****************************************************************************
+ * Name: exited_child
+ *
+ * Description:
+ * Handle the case where a child exited properlay was we (apparently) lost
+ * the detch of child signal.
+ *
+ *****************************************************************************/
+
+#ifdef CONFIG_SCHED_CHILD_STATUS
+static void exited_child(FAR _TCB *rtcb, FAR struct child_status_s *child,
+ FAR siginfo_t *info)
+{
+ /* The child has exited. Return the saved exit status (and some fudged
+ * information.
+ */
+
+ info->si_signo = SIGCHLD;
+ info->si_code = CLD_EXITED;
+ info->si_value.sival_ptr = NULL;
+ info->si_pid = child->ch_pid;
+ info->si_status = child->ch_status;
+
+ /* Discard the child entry */
+
+ (void)group_removechild(rtcb->group, child->ch_pid);
+ group_freechild(child);
+}
+#endif
+
+/*****************************************************************************
* Public Functions
*****************************************************************************/
@@ -120,9 +151,14 @@
*
*****************************************************************************/
-int waitid(idtype_t idtype, id_t id, siginfo_t *info, int options)
+int waitid(idtype_t idtype, id_t id, FAR siginfo_t *info, int options)
{
FAR _TCB *rtcb = (FAR _TCB *)g_readytorun.head;
+ FAR _TCB *ctcb;
+#ifdef CONFIG_SCHED_CHILD_STATUS
+ FAR struct child_status_s *child;
+ bool retains;
+#endif
sigset_t sigset;
int err;
int ret;
@@ -160,7 +196,11 @@ int waitid(idtype_t idtype, id_t id, siginfo_t *info, int options)
*/
#ifdef CONFIG_SCHED_CHILD_STATUS
- if (rtcb->children == NULL)
+ /* Does this task retain child status? */
+
+ retains = ((rtcb->group->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0);
+
+ if (rtcb->group->tg_children == NULL && retains)
{
/* There are no children */
@@ -169,13 +209,33 @@ int waitid(idtype_t idtype, id_t id, siginfo_t *info, int options)
}
else if (idtype == P_PID)
{
- if (task_findchild(rtcb, (pid_t)id) == NULL)
- {
- /* This specific pid is not a child */
+ /* Get the TCB corresponding to this PID and make sure it is our child. */
+ ctcb = sched_gettcb((pid_t)id);
+#ifdef HAVE_GROUP_MEMBERS
+ if (!ctcb || ctcb->group->tg_pgid != rtcb->group->tg_gid)
+#else
+ if (!ctcb || ctcb->ppid != rtcb->pid)
+#endif
+ {
err = ECHILD;
goto errout_with_errno;
}
+
+ /* Does this task retain child status? */
+
+ if (retains)
+ {
+ /* Check if this specific pid has allocated child status? */
+
+ if (group_findchild(rtcb->group, (pid_t)id) == NULL)
+ {
+ /* This specific pid is not a child */
+
+ err = ECHILD;
+ goto errout_with_errno;
+ }
+ }
}
#else
if (rtcb->nchildren == 0)
@@ -189,8 +249,12 @@ int waitid(idtype_t idtype, id_t id, siginfo_t *info, int options)
{
/* 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)
+ ctcb = sched_gettcb((pid_t)id);
+#ifdef HAVE_GROUP_MEMBERS
+ if (!ctcb || ctcb->group->tg_pgid != rtcb->group->tg_gid)
+#else
+ if (!ctcb || ctcb->ppid != rtcb->pid)
+#endif
{
err = ECHILD;
goto errout_with_errno;
@@ -209,48 +273,61 @@ int waitid(idtype_t idtype, id_t id, siginfo_t *info, int options)
* instead).
*/
- DEBUGASSERT(rtcb->children);
- if (rtcb->children == NULL)
+ DEBUGASSERT(!retains || rtcb->group->tg_children);
+ if (idtype == P_ALL)
{
- /* This should not happen. I am just wasting your FLASH. */
+ /* We are waiting for any child to exit */
- err = ECHILD;
- goto errout_with_errno;
- }
- else if (idtype == P_PID)
- {
- FAR struct child_status_s *child;
-
- /* We are waiting for a specific PID. Get the current status
- * of the child task.
- */
-
- child = task_findchild(rtcb, (pid_t)id);
- DEBUGASSERT(child);
- if (!child)
+ if (retains && (child = group_exitchild(rtcb->group)) != NULL)
{
- /* Yikes! The child status entry just disappeared! */
+ /* A child has exited. Apparently we missed the signal.
+ * Return the exit status and break out of the loop.
+ */
- err = ECHILD;
- goto errout_with_errno;
+ exited_child(rtcb, child, info);
+ break;
}
+ }
+ /* We are waiting for a specific PID. Does this task retain child status? */
+
+ else if (retains)
+ {
+ /* Yes ... Get the current status of the child task. */
+
+ child = group_findchild(rtcb->group, (pid_t)id);
+ DEBUGASSERT(child);
+
/* Did the child exit? */
if ((child->ch_flags & CHILD_FLAG_EXITED) != 0)
{
- /* The child has exited. Return the saved exit status */
+ /* The child has exited. Return the exit status and break out
+ * of the loop.
+ */
- info->si_signo = SIGCHLD;
- info->si_code = CLD_EXITED;
- info->si_value.sival_ptr = NULL;
- info->si_pid = (pid_t)id;
- info->si_status = child->ch_status;
+ exited_child(rtcb, child, info);
+ break;
+ }
+ }
+ else
+ {
+ /* We can use kill() with signal number 0 to determine if that
+ * task is still alive.
+ */
- /* Discard the child entry and break out of the loop */
+ ret = kill((pid_t)id, 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 than bogus status.
+ */
- (void)task_removechild(rtcb, (pid_t)id);
- task_freechild(child);
+ err = ECHILD;
+ goto errout_with_errno;
}
}
#else
diff --git a/nuttx/sched/sched_waitpid.c b/nuttx/sched/sched_waitpid.c
index fe3f7167d..0285c2673 100644
--- a/nuttx/sched/sched_waitpid.c
+++ b/nuttx/sched/sched_waitpid.c
@@ -47,6 +47,7 @@
#include <nuttx/sched.h>
#include "os_internal.h"
+#include "group_internal.h"
#ifdef CONFIG_SCHED_WAITPID
@@ -171,21 +172,17 @@
*
* Assumptions:
*
- *****************************************************************************/
-
-/***************************************************************************
- * 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.
+ * Compatibility
+ * 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;
+ _TCB *ctcb;
bool mystat;
int err;
int ret;
@@ -208,8 +205,8 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options)
/* Get the TCB corresponding to this PID */
- tcb = sched_gettcb(pid);
- if (!tcb)
+ ctcb = sched_gettcb(pid);
+ if (!ctcb)
{
err = ECHILD;
goto errout_with_errno;
@@ -221,15 +218,15 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options)
* others?
*/
- if (stat_loc != NULL && tcb->stat_loc == NULL)
+ if (stat_loc != NULL && ctcb->stat_loc == NULL)
{
- tcb->stat_loc = stat_loc;
- mystat = true;
+ ctcb->stat_loc = stat_loc;
+ mystat = true;
}
/* Then wait for the task to exit */
- ret = sem_wait(&tcb->exitsem);
+ ret = sem_wait(&ctcb->exitsem);
if (ret < 0)
{
/* Unlock pre-emption and return the ERROR (sem_wait has already set
@@ -239,7 +236,7 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options)
if (mystat)
{
- tcb->stat_loc = NULL;
+ ctcb->stat_loc = NULL;
}
goto errout;
@@ -274,8 +271,10 @@ errout:
pid_t waitpid(pid_t pid, int *stat_loc, int options)
{
FAR _TCB *rtcb = (FAR _TCB *)g_readytorun.head;
+ FAR _TCB *ctcb;
#ifdef CONFIG_SCHED_CHILD_STATUS
FAR struct child_status_s *child;
+ bool retains;
#endif
FAR struct siginfo info;
sigset_t sigset;
@@ -303,27 +302,47 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options)
sched_lock();
- /* Verify that this task actually has children and that the the request
- * TCB is actually a child of this task.
+ /* Verify that this task actually has children and that the requested PID
+ * is actually a child of this task.
*/
#ifdef CONFIG_SCHED_CHILD_STATUS
- if (rtcb->children == NULL)
- {
- /* There are no children */
+ /* Does this task retain child status? */
+ retains = ((rtcb->group->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0);
+
+ if (rtcb->group->tg_children == NULL && retains)
+ {
err = ECHILD;
goto errout_with_errno;
}
else if (pid != (pid_t)-1)
{
- /* This specific pid is not a child */
+ /* Get the TCB corresponding to this PID and make sure it is our child. */
- if (task_findchild(rtcb, pid) == NULL)
+ ctcb = sched_gettcb(pid);
+#ifdef HAVE_GROUP_MEMBERS
+ if (!ctcb || ctcb->group->tg_pgid != rtcb->group->tg_gid)
+#else
+ if (!ctcb || ctcb->ppid != rtcb->pid)
+#endif
{
err = ECHILD;
goto errout_with_errno;
}
+
+ /* Does this task retain child status? */
+
+ if (retains)
+ {
+ /* Check if this specific pid has allocated child status? */
+
+ if (group_findchild(rtcb->group, pid) == NULL)
+ {
+ err = ECHILD;
+ goto errout_with_errno;
+ }
+ }
}
#else
if (rtcb->nchildren == 0)
@@ -337,8 +356,12 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options)
{
/* 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)
+ ctcb = sched_gettcb(pid);
+#ifdef HAVE_GROUP_MEMBERS
+ if (!ctcb || ctcb->group->tg_pgid != rtcb->group->tg_gid)
+#else
+ if (!ctcb || ctcb->ppid != rtcb->pid)
+#endif
{
err = ECHILD;
goto errout_with_errno;
@@ -350,6 +373,7 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options)
for (;;)
{
+#ifdef CONFIG_SCHED_CHILD_STATUS
/* 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
@@ -362,39 +386,33 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options)
* chilren.
*/
-#ifdef CONFIG_SCHED_CHILD_STATUS
- DEBUGASSERT(rtcb->children);
- if (rtcb->children == NULL)
-#else
- if (rtcb->nchildren == 0)
-#endif
+ DEBUGASSERT(!retains || rtcb->group->tg_children);
+ if (retains && (child = group_exitchild(rtcb->group)) != NULL)
{
- /* 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.
+ /* A child has exited. Apparently we missed the signal.
+ * Return the saved exit status.
*/
- err = ECHILD;
- goto errout_with_errno;
+ /* The child has exited. Return the saved exit status */
+
+ *stat_loc = child->ch_status << 8;
+
+ /* Discard the child entry and break out of the loop */
+
+ (void)group_removechild(rtcb->group, child->ch_pid);
+ group_freechild(child);
+ break;
}
}
- else
+
+ /* We are waiting for a specific PID. Does this task retain child status? */
+
+ else if (retains)
{
-#ifdef CONFIG_SCHED_CHILD_STATUS
- /* We are waiting for a specific PID. Get the current status
- * of the child task.
- */
+ /* Get the current status of the child task. */
- child = task_findchild(rtcb, pid);
+ child = group_findchild(rtcb->group, pid);
DEBUGASSERT(child);
- if (!child)
- {
- /* Yikes! The child status entry just disappeared! */
-
- err = ECHILD;
- goto errout_with_errno;
- }
/* Did the child exit? */
@@ -402,33 +420,54 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options)
{
/* The child has exited. Return the saved exit status */
- *stat_loc = child->ch_status;
+ *stat_loc = child->ch_status << 8;
/* Discard the child entry and break out of the loop */
- (void)task_removechild(rtcb, pid);
- task_freechild(child);
+ (void)group_removechild(rtcb->group, pid);
+ group_freechild(child);
+ break;
}
-#else
- /* We are waiting for a specific PID. We can use kill() with
- * signal number 0 to determine if that task is still alive.
+ }
+ else
+ {
+ /* 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.
+ /* 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 than bogus status.
*/
err = ECHILD;
goto errout_with_errno;
}
-#endif
}
+#else
+ /* 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 ||
+ (pid != (pid_t)-1 && (ret = kill(pid, 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;
+ }
+#endif
/* Wait for any death-of-child signal */
@@ -447,7 +486,7 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options)
{
/* Yes... return the status and PID (in the event it was -1) */
- *stat_loc = info.si_status;
+ *stat_loc = info.si_status << 8;
pid = info.si_pid;
break;
}
diff --git a/nuttx/sched/sig_action.c b/nuttx/sched/sig_action.c
index 708667993..5c00179dc 100644
--- a/nuttx/sched/sig_action.c
+++ b/nuttx/sched/sig_action.c
@@ -46,6 +46,7 @@
#include <errno.h>
#include "os_internal.h"
+#include "group_internal.h"
#include "sig_internal.h"
/****************************************************************************
@@ -169,7 +170,6 @@ int sigaction(int signo, FAR const struct sigaction *act, FAR struct sigaction *
{
FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
FAR sigactq_t *sigact;
- int ret;
/* Since sigactions can only be installed from the running thread of
* execution, no special precautions should be necessary.
@@ -238,11 +238,11 @@ int sigaction(int signo, FAR const struct sigaction *act, FAR struct sigaction *
/* Mark that status should be not be retained */
- rtcb->flags |= TCB_FLAG_NOCLDWAIT;
+ rtcb->group->tg_flags |= GROUP_FLAG_NOCLDWAIT;
/* Free all pending exit status */
- task_removechildren(rtcb);
+ group_removechildren(rtcb->group);
irqrestore(flags);
}
#endif
@@ -251,24 +251,31 @@ int sigaction(int signo, FAR const struct sigaction *act, FAR struct sigaction *
if (act->sa_u._sa_handler == SIG_IGN)
{
- /* If there is a old sigaction, remove it from sigactionq */
+ /* Do we still have a sigaction container from the previous setting? */
- sq_rem((FAR sq_entry_t*)sigact, &rtcb->sigactionq);
+ if (sigact)
+ {
+ /* Yes.. Remove it from sigactionq */
+
+ sq_rem((FAR sq_entry_t*)sigact, &rtcb->sigactionq);
- /* And deallocate it */
+ /* And deallocate it */
- sig_releaseaction(sigact);
+ sig_releaseaction(sigact);
+ }
}
/* A sigaction has been supplied */
else
{
- /* Check if a sigaction was found */
+ /* Do we still have a sigaction container from the previous setting?
+ * If so, then re-use for the new signal action.
+ */
if (!sigact)
{
- /* No sigaction was found, but one is needed. Allocate one. */
+ /* No.. Then we need to allocate one for the new action. */
sigact = sig_allocateaction();
@@ -294,7 +301,7 @@ int sigaction(int signo, FAR const struct sigaction *act, FAR struct sigaction *
COPY_SIGACTION(&sigact->act, act);
}
- return ret;
+ return OK;
}
/****************************************************************************
diff --git a/nuttx/sched/task_create.c b/nuttx/sched/task_create.c
index 2ed929ab0..944743200 100644
--- a/nuttx/sched/task_create.c
+++ b/nuttx/sched/task_create.c
@@ -48,7 +48,7 @@
#include <nuttx/kmalloc.h>
#include "os_internal.h"
-#include "env_internal.h"
+#include "group_internal.h"
/****************************************************************************
* Definitions
@@ -108,6 +108,7 @@ static int thread_create(const char *name, uint8_t ttype, int priority,
{
FAR _TCB *tcb;
pid_t pid;
+ int errcode;
int ret;
/* Allocate a TCB for the new task. */
@@ -115,29 +116,39 @@ static int thread_create(const char *name, uint8_t ttype, int priority,
tcb = (FAR _TCB*)kzalloc(sizeof(_TCB));
if (!tcb)
{
+ errcode = ENOMEM;
goto errout;
}
+ /* Allocate a new task group */
+
+#ifdef HAVE_TASK_GROUP
+ ret = group_allocate(tcb);
+ if (ret < 0)
+ {
+ errcode = -ret;
+ goto errout_with_tcb;
+ }
+#endif
+
/* Associate file descriptors with the new task */
#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
- ret = sched_setuptaskfiles(tcb);
+ ret = group_setuptaskfiles(tcb);
if (ret != OK)
{
+ errcode = -ret;
goto errout_with_tcb;
}
#endif
- /* Clone the parent's task environment */
-
- (void)env_dup(tcb);
-
/* Allocate the stack for the TCB */
#ifndef CONFIG_CUSTOM_STACK
ret = up_create_stack(tcb, stack_size);
if (ret != OK)
{
+ errcode = -ret;
goto errout_with_tcb;
}
#endif
@@ -145,8 +156,9 @@ 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;
}
@@ -154,6 +166,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;
@@ -163,6 +186,8 @@ static int thread_create(const char *name, uint8_t ttype, int priority,
ret = task_activate(tcb);
if (ret != OK)
{
+ errcode = get_errno();
+
/* The TCB was added to the active task list by task_schedsetup() */
dq_rem((FAR dq_entry_t*)tcb, (dq_queue_t*)&g_inactivetasks);
@@ -175,7 +200,7 @@ errout_with_tcb:
sched_releasetcb(tcb);
errout:
- errno = ENOMEM;
+ set_errno(errcode);
return ERROR;
}
diff --git a/nuttx/sched/task_exithook.c b/nuttx/sched/task_exithook.c
index 1813c12ed..889df25e0 100644
--- a/nuttx/sched/task_exithook.c
+++ b/nuttx/sched/task_exithook.c
@@ -49,6 +49,7 @@
#include <nuttx/fs/fs.h>
#include "os_internal.h"
+#include "group_internal.h"
#include "sig_internal.h"
/****************************************************************************
@@ -103,10 +104,7 @@ static inline void task_atexit(FAR _TCB *tcb)
(*tcb->atexitfunc[index])();
- /* Nullify the atexit function. task_exithook may be called more then
- * once in most task exit scenarios. Nullifying the atext function
- * pointer will assure that the callback is performed only once.
- */
+ /* Nullify the atexit function to prevent its reuse. */
tcb->atexitfunc[index] = NULL;
}
@@ -119,10 +117,7 @@ static inline void task_atexit(FAR _TCB *tcb)
(*tcb->atexitfunc)();
- /* Nullify the atexit function. task_exithook may be called more then
- * once in most task exit scenarios. Nullifying the atext function
- * pointer will assure that the callback is performed only once.
- */
+ /* Nullify the atexit function to prevent its reuse. */
tcb->atexitfunc = NULL;
}
@@ -160,10 +155,7 @@ static inline void task_onexit(FAR _TCB *tcb, int status)
(*tcb->onexitfunc[index])(status, tcb->onexitarg[index]);
- /* Nullify the on_exit function. task_exithook may be called more then
- * once in most task exit scenarios. Nullifying the atext function
- * pointer will assure that the callback is performed only once.
- */
+ /* Nullify the on_exit function to prevent its reuse. */
tcb->onexitfunc[index] = NULL;
}
@@ -175,10 +167,7 @@ static inline void task_onexit(FAR _TCB *tcb, int status)
(*tcb->onexitfunc)(status, tcb->onexitarg);
- /* Nullify the on_exit function. task_exithook may be called more then
- * once in most task exit scenarios. Nullifying the on_exit function
- * pointer will assure that the callback is performed only once.
- */
+ /* Nullify the on_exit function to prevent its reuse. */
tcb->onexitfunc = NULL;
}
@@ -189,6 +178,89 @@ static inline void task_onexit(FAR _TCB *tcb, int status)
#endif
/****************************************************************************
+ * Name: task_exitstatus
+ *
+ * Description:
+ * Report exit status when main task of a task group exits
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_SCHED_CHILD_STATUS
+static inline void task_exitstatus(FAR struct task_group_s *group, int status)
+{
+ FAR struct child_status_s *child;
+
+ /* Check if the parent task group has suppressed retention of
+ * child exit status information.
+ */
+
+ if ((group->tg_flags & GROUP_FLAG_NOCLDWAIT) == 0)
+ {
+ /* No.. Find the exit status entry for this task in the parent TCB */
+
+ child = group_findchild(group, getpid());
+ DEBUGASSERT(child);
+ if (child)
+ {
+#ifndef HAVE_GROUP_MEMBERS
+ /* No group members? Save the exit status */
+
+ child->ch_status = status;
+#endif
+ /* Save the exit status.. For the case of HAVE_GROUP_MEMBERS,
+ * the child status will be as exited until the last member
+ * of the task group exits.
+ */
+
+ child->ch_status = status;
+ }
+ }
+}
+#else
+
+# define task_exitstatus(group,status)
+
+#endif /* CONFIG_SCHED_CHILD_STATUS */
+
+/****************************************************************************
+ * Name: task_groupexit
+ *
+ * Description:
+ * Mark that the final thread of a child task group as exited.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_SCHED_CHILD_STATUS
+static inline void task_groupexit(FAR struct task_group_s *group)
+{
+ FAR struct child_status_s *child;
+
+ /* Check if the parent task group has suppressed retention of child exit
+ * status information.
+ */
+
+ if ((group->tg_flags & GROUP_FLAG_NOCLDWAIT) == 0)
+ {
+ /* No.. Find the exit status entry for this task in the parent TCB */
+
+ child = group_findchild(group, getpid());
+ DEBUGASSERT(child);
+ if (child)
+ {
+ /* Mark that all members of the child task group has exit'ed */
+
+ child->ch_flags |= CHILD_FLAG_EXITED;
+ }
+ }
+}
+
+#else
+
+# define task_groupexit(group)
+
+#endif /* CONFIG_SCHED_CHILD_STATUS */
+
+/****************************************************************************
* Name: task_sigchild
*
* Description:
@@ -197,72 +269,96 @@ static inline void task_onexit(FAR _TCB *tcb, int status)
****************************************************************************/
#ifdef CONFIG_SCHED_HAVE_PARENT
-static inline void task_sigchild(FAR _TCB *tcb, int status)
+#ifdef HAVE_GROUP_MEMBERS
+static inline void task_sigchild(gid_t pgid, FAR _TCB *ctcb, int status)
{
- FAR _TCB *ptcb;
+ FAR struct task_group_s *chgrp = ctcb->group;
+ FAR struct task_group_s *pgrp;
siginfo_t info;
- /* Only exiting tasks should generate SIGCHLD. pthreads use other
- * mechansims.
+ DEBUGASSERT(chgrp);
+
+ /* Get the parent task group. It is possible that all of the members of
+ * the parent task group have exited. This would not be an error. In
+ * this case, the child task group has been orphaned.
*/
- if ((tcb->flags & TCB_FLAG_TTYPE_MASK) == TCB_FLAG_TTYPE_TASK)
+ pgrp = group_find(chgrp->tg_pgid);
+ if (!pgrp)
{
- /* Keep things stationary through the following */
+ /* Set the task group ID to an invalid group ID. The dead parent
+ * task group ID could get reused some time in the future.
+ */
- sched_lock();
+ chgrp->tg_pgid = INVALID_GROUP_ID;
+ return;
+ }
- /* Get the TCB of the receiving task */
+ /* Save the exit status now if this is the main thread of the task group
+ * that is exiting. Only the exiting main task of a task group carries
+ * interpretable exit Check if this is the main task that is exiting.
+ */
- ptcb = sched_gettcb(tcb->parent);
- if (!ptcb)
- {
- /* The parent no longer exists... bail */
+ if ((ctcb->flags & TCB_FLAG_TTYPE_MASK) == TCB_FLAG_TTYPE_TASK)
+ {
+ task_exitstatus(pgrp, status);
+ }
- sched_unlock();
- return;
- }
+ /* But only the final exiting thread in a task group, whatever it is,
+ * should generate SIGCHLD.
+ */
-#ifdef CONFIG_SCHED_CHILD_STATUS
- /* Check if the parent task has suppressed retention of child exit
- * status information. Only 'tasks' report exit status, not pthreads.
- * pthreads have a different mechanism.
+ if (chgrp->tg_nmembers == 1)
+ {
+ /* Mark that all of the threads in the task group have exited */
+
+ task_groupexit(pgrp);
+
+ /* 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.
*/
- if ((ptcb->flags & TCB_FLAG_NOCLDWAIT) == 0)
- {
- FAR struct child_status_s *child;
+ info.si_signo = SIGCHLD;
+ info.si_code = CLD_EXITED;
+ info.si_value.sival_ptr = NULL;
+ info.si_pid = ctcb->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.
+ */
- /* No.. Find the exit status entry for this task in the parent TCB */
+ (void)group_signal(pgrp, &info);
+ }
+}
- child = task_findchild(ptcb, getpid());
- DEBUGASSERT(child);
- if (child)
- {
- /* Mark that the child has exit'ed */
+#else /* HAVE_GROUP_MEMBERS */
- child->ch_flags |= CHILD_FLAG_EXITED;
+static inline void task_sigchild(FAR _TCB *ptcb, FAR _TCB *ctcb, int status)
+{
+ siginfo_t info;
- /* Save the exit status */
+ /* If task groups are not supported then we will report SIGCHLD when the
+ * task exits. Unfortunately, there could still be threads in the group
+ * that are still running.
+ */
+
+ if ((ctcb->flags & TCB_FLAG_TTYPE_MASK) == TCB_FLAG_TTYPE_TASK)
+ {
+#ifdef CONFIG_SCHED_CHILD_STATUS
+ /* Save the exit status now of the main thread */
+
+ task_exitstatus(ptcb->group, status);
+
+#else /* CONFIG_SCHED_CHILD_STATUS */
- child->ch_status = status;
- }
- }
-#else
/* Decrement the number of children from this parent */
DEBUGASSERT(ptcb->nchildren > 0);
ptcb->nchildren--;
-#endif
- /* 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;
+#endif /* CONFIG_SCHED_CHILD_STATUS */
/* 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
@@ -272,7 +368,7 @@ static inline void task_sigchild(FAR _TCB *tcb, int status)
info.si_signo = SIGCHLD;
info.si_code = CLD_EXITED;
info.si_value.sival_ptr = NULL;
- info.si_pid = tcb->pid;
+ info.si_pid = ctcb->pid;
info.si_status = status;
/* Send the signal. We need to use this internal interface so that we
@@ -280,11 +376,72 @@ static inline void task_sigchild(FAR _TCB *tcb, int status)
*/
(void)sig_received(ptcb, &info);
+ }
+}
+
+#endif /* HAVE_GROUP_MEMBERS */
+#else /* CONFIG_SCHED_HAVE_PARENT */
+
+# define task_sigchild(x,ctcb,status)
+
+#endif /* CONFIG_SCHED_HAVE_PARENT */
+
+/****************************************************************************
+ * Name: task_leavegroup
+ *
+ * Description:
+ * Send the SIGCHILD signal to the parent thread
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_SCHED_HAVE_PARENT
+static inline void task_leavegroup(FAR _TCB *ctcb, int status)
+{
+#ifdef HAVE_GROUP_MEMBERS
+ DEBUGASSERT(ctcb && ctcb->group);
+
+ /* Keep things stationary throughout the following */
+
+ sched_lock();
+
+ /* Send SIGCHLD to all members of the parent's task group */
+
+ task_sigchild(ctcb->group->tg_pgid, ctcb, status);
+ sched_unlock();
+#else
+ FAR _TCB *ptcb;
+
+ /* Keep things stationary throughout the following */
+
+ sched_lock();
+
+ /* Get the TCB of the receiving, parent task. We do this early to
+ * handle multiple calls to task_leavegroup. ctcb->ppid is set to an
+ * invalid value below and the following call will fail if we are
+ * called again.
+ */
+
+ ptcb = sched_gettcb(ctcb->ppid);
+ if (!ptcb)
+ {
+ /* The parent no longer exists... bail */
+
sched_unlock();
+ return;
}
+
+ /* Send SIGCHLD to all members of the parent's task group */
+
+ task_sigchild(ptcb, ctcb, status);
+
+ /* Forget who our parent was */
+
+ ctcb->ppid = INVALID_PROCESS_ID;
+ sched_unlock();
+#endif
}
#else
-# define task_sigchild(tcb,status)
+# define task_leavegroup(ctcb,status)
#endif
/****************************************************************************
@@ -352,6 +509,16 @@ static inline void task_exitwakeup(FAR _TCB *tcb, int status)
void task_exithook(FAR _TCB *tcb, int status)
{
+ /* Under certain conditions, task_exithook() can be called multiple times.
+ * A bit in the TCB was set the first time this function was called. If
+ * that bit is set, then just ext doing nothing more..
+ */
+
+ if ((tcb->flags & TCB_FLAG_EXIT_PROCESSING) != 0)
+ {
+ return;
+ }
+
/* If exit function(s) were registered, call them now before we do any un-
* initialization. NOTE: In the case of task_delete(), the exit function
* will *not* be called on the thread execution of the task being deleted!
@@ -363,9 +530,9 @@ void task_exithook(FAR _TCB *tcb, int status)
task_onexit(tcb, status);
- /* Send SIGCHLD to the parent of the exit-ing task */
+ /* Leave the task group */
- task_sigchild(tcb, status);
+ task_leavegroup(tcb, status);
/* Wakeup any tasks waiting for this task to exit */
@@ -376,26 +543,27 @@ void task_exithook(FAR _TCB *tcb, int status)
*/
#if CONFIG_NFILE_STREAMS > 0
- (void)lib_flushall(tcb->streams);
+ (void)lib_flushall(&tcb->group->tg_streamlist);
#endif
- /* Discard any un-reaped child status (no zombies here!) */
+ /* Leave the task group. Perhaps discarding any un-reaped child
+ * status (no zombies here!)
+ */
-#if defined(CONFIG_SCHED_HAVE_PARENT) && defined(CONFIG_SCHED_CHILD_STATUS)
- task_removechildren(tcb);
+#ifdef HAVE_TASK_GROUP
+ group_leave(tcb);
#endif
- /* Free all file-related resources now. This gets called again
- * just be be certain when the TCB is delallocated. However, we
- * really need to close files as soon as possible while we still
- * have a functioning task.
- */
-
- (void)sched_releasefiles(tcb);
-
/* Deallocate anything left in the TCB's queues */
#ifndef CONFIG_DISABLE_SIGNALS
sig_cleanup(tcb); /* Deallocate Signal lists */
#endif
+
+ /* This function can be re-entered in certain cases. Set a flag
+ * bit in the TCB to not that we have already completed this exit
+ * processing.
+ */
+
+ tcb->flags |= TCB_FLAG_EXIT_PROCESSING;
}
diff --git a/nuttx/sched/task_init.c b/nuttx/sched/task_init.c
index 0f0fdc68e..78f35bc2a 100644
--- a/nuttx/sched/task_init.c
+++ b/nuttx/sched/task_init.c
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/task_init.c
*
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -42,10 +42,12 @@
#include <sys/types.h>
#include <stdint.h>
#include <sched.h>
+#include <errno.h>
+
#include <nuttx/arch.h>
#include "os_internal.h"
-#include "env_internal.h"
+#include "group_internal.h"
/****************************************************************************
* Definitions
@@ -102,10 +104,10 @@
* parameters are required, argv may be NULL.
*
* Return Value:
- * OK on success; ERROR on failure. (See task_schedsetup() for possible
- * failure conditions). On failure, the caller is responsible for freeing
- * the stack memory and for calling sched_releasetcb() to free the TCB
- * (which could be in most any state).
+ * OK on success; ERROR on failure with errno set appropriately. (See
+ * task_schedsetup() for possible failure conditions). On failure, the
+ * caller is responsible for freeing the stack memory and for calling
+ * sched_releasetcb() to free the TCB (which could be in most any state).
*
****************************************************************************/
@@ -118,20 +120,30 @@ int task_init(FAR _TCB *tcb, const char *name, int priority,
main_t entry, const char *argv[])
#endif
{
+ int errcode;
int ret;
- /* Associate file descriptors with the new task */
+ /* Create a new task group */
-#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
- if (sched_setuptaskfiles(tcb) != OK)
+#ifdef HAVE_TASK_GROUP
+ ret = group_allocate(tcb);
+ if (ret < 0)
{
- return ERROR;
+ errcode = -ret;
+ goto errout;
}
#endif
- /* Clone the parent's task environment */
+ /* Associate file descriptors with the new task */
- (void)env_dup(tcb);
+#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
+ ret = group_setuptaskfiles(tcb);
+ if (ret < 0)
+ {
+ errcode = -ret;
+ goto errout_with_group;
+ }
+#endif
/* Configure the user provided stack region */
@@ -143,13 +155,35 @@ int task_init(FAR _TCB *tcb, const char *name, int priority,
ret = task_schedsetup(tcb, priority, task_start, entry,
TCB_FLAG_TTYPE_TASK);
- if (ret == OK)
+ if (ret < OK)
{
- /* Setup to pass parameters to the new task */
+ errcode = -ret;
+ goto errout_with_group;
+ }
+
+ /* 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 */
- (void)task_argsetup(tcb, name, argv);
+#ifdef HAVE_TASK_GROUP
+ ret = group_initialize(tcb);
+ if (ret < 0)
+ {
+ errcode = -ret;
+ goto errout_with_group;
}
+#endif
+ return OK;
- return ret;
+errout_with_group:
+#ifdef HAVE_TASK_GROUP
+ group_leave(tcb);
+
+errout:
+#endif
+ set_errno(errcode);
+ return ERROR;
}
diff --git a/nuttx/sched/task_posixspawn.c b/nuttx/sched/task_posixspawn.c
index 7bb9c9a4d..e9ad1fc45 100644
--- a/nuttx/sched/task_posixspawn.c
+++ b/nuttx/sched/task_posixspawn.c
@@ -54,6 +54,7 @@
#include <nuttx/spawn.h>
#include "os_internal.h"
+#include "group_internal.h"
/****************************************************************************
* Private Types
diff --git a/nuttx/sched/task_reparent.c b/nuttx/sched/task_reparent.c
index 28d371bf1..5bb62893f 100644
--- a/nuttx/sched/task_reparent.c
+++ b/nuttx/sched/task_reparent.c
@@ -42,6 +42,7 @@
#include <errno.h>
#include "os_internal.h"
+#include "group_internal.h"
#ifdef CONFIG_SCHED_HAVE_PARENT
@@ -69,6 +70,141 @@
*
*****************************************************************************/
+#ifdef HAVE_GROUP_MEMBERS
+int task_reparent(pid_t ppid, pid_t chpid)
+{
+#ifdef CONFIG_SCHED_CHILD_STATUS
+ FAR struct child_status_s *child;
+#endif
+ FAR struct task_group_s *chgrp;
+ FAR struct task_group_s *ogrp;
+ FAR struct task_group_s *pgrp;
+ _TCB *tcb;
+ gid_t ogid;
+ gid_t pgid;
+ irqstate_t flags;
+ int ret;
+
+ /* Disable interrupts so that nothing can change in the relatinoship of
+ * the three task: Child, current parent, and new parent.
+ */
+
+ flags = irqsave();
+
+ /* Get the child tasks task group */
+
+ tcb = sched_gettcb(chpid);
+ if (!tcb)
+ {
+ ret = -ECHILD;
+ goto errout_with_ints;
+ }
+
+ DEBUGASSERT(tcb->group);
+ chgrp = tcb->group;
+
+ /* Get the GID of the old parent task's task group (ogid) */
+
+ ogid = chgrp->tg_pgid;
+
+ /* Get the old parent task's task group (ogrp) */
+
+ ogrp = group_find(ogid);
+ if (!ogrp)
+ {
+ ret = -ESRCH;
+ goto errout_with_ints;
+ }
+
+ /* If new parent task's PID (ppid) is zero, then new parent is the
+ * grandparent will be the new parent, i.e., the parent of the current
+ * parent task.
+ */
+
+ if (ppid == 0)
+ {
+ /* Get the grandparent task's task group (pgrp) */
+
+ pgid = ogrp->tg_pgid;
+ pgrp = group_find(pgid);
+ }
+ else
+ {
+ /* Get the new parent task's task group (pgrp) */
+
+ tcb = sched_gettcb(ppid);
+ if (!tcb)
+ {
+ ret = -ESRCH;
+ goto errout_with_ints;
+ }
+
+ pgrp = tcb->group;
+ pgid = pgrp->tg_gid;
+ }
+
+ if (!pgrp)
+ {
+ ret = -ESRCH;
+ goto errout_with_ints;
+ }
+
+ /* Then reparent the child. Notice that we don't actually change the
+ * parent of the task. Rather, we change the parent task group for
+ * all members of the child's task group.
+ */
+
+ chgrp->tg_pgid = pgid;
+
+#ifdef CONFIG_SCHED_CHILD_STATUS
+ /* Remove the child status entry from old parent task group */
+
+ child = group_removechild(ogrp, chpid);
+ if (child)
+ {
+ /* Has the new parent's task group supressed child exit status? */
+
+ if ((pgrp->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0)
+ {
+ /* No.. Add the child status entry to the new parent's task group */
+
+ group_addchild(pgrp, child);
+ }
+ else
+ {
+ /* Yes.. Discard the child status entry */
+
+ group_freechild(child);
+ }
+
+ /* Either case is a success */
+
+ ret = OK;
+ }
+ else
+ {
+ /* This would not be an error if the original parent's task group has
+ * suppressed child exit status.
+ */
+
+ ret = ((ogrp->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0) ? -ENOENT : OK;
+ }
+
+#else /* CONFIG_SCHED_CHILD_STATUS */
+
+ DEBUGASSERT(otcb->nchildren > 0);
+
+ otcb->nchildren--; /* The orignal parent now has one few children */
+ ptcb->nchildren++; /* The new parent has one additional child */
+ ret = OK;
+
+#endif /* CONFIG_SCHED_CHILD_STATUS */
+
+errout_with_ints:
+ irqrestore(flags);
+ return ret;
+}
+#else
int task_reparent(pid_t ppid, pid_t chpid)
{
#ifdef CONFIG_SCHED_CHILD_STATUS
@@ -98,7 +234,7 @@ int task_reparent(pid_t ppid, pid_t chpid)
/* Get the PID of the child task's parent (opid) */
- opid = chtcb->parent;
+ opid = chtcb->ppid;
/* Get the TCB of the child task's parent (otcb) */
@@ -116,7 +252,7 @@ int task_reparent(pid_t ppid, pid_t chpid)
if (ppid == 0)
{
- ppid = otcb->parent;
+ ppid = otcb->ppid;
}
/* Get the new parent task's TCB (ptcb) */
@@ -130,34 +266,55 @@ int task_reparent(pid_t ppid, pid_t chpid)
/* Then reparent the child */
- chtcb->parent = ppid; /* The task specified by ppid is the new parent */
+ chtcb->ppid = ppid; /* The task specified by ppid is the new parent */
#ifdef CONFIG_SCHED_CHILD_STATUS
/* Remove the child status entry from old parent TCB */
- child = task_removechild(otcb, chpid);
+ child = group_removechild(otcb->group, chpid);
if (child)
{
- /* Add the child status entry to the new parent TCB */
+ /* Has the new parent's task group supressed child exit status? */
+
+ if ((ptcb->group->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0)
+ {
+ /* No.. Add the child status entry to the new parent's task group */
+
+ group_addchild(ptcb->group, child);
+ }
+ else
+ {
+ /* Yes.. Discard the child status entry */
+
+ group_freechild(child);
+ }
+
+ /* Either case is a success */
- task_addchild(ptcb, child);
ret = OK;
}
else
{
- ret = -ENOENT;
+ /* This would not be an error if the original parent's task group has
+ * suppressed child exit status.
+ */
+
+ ret = ((otcb->group->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0) ? -ENOENT : OK;
}
-#else
+
+#else /* CONFIG_SCHED_CHILD_STATUS */
+
DEBUGASSERT(otcb->nchildren > 0);
otcb->nchildren--; /* The orignal parent now has one few children */
ptcb->nchildren++; /* The new parent has one additional child */
ret = OK;
-#endif
+
+#endif /* CONFIG_SCHED_CHILD_STATUS */
errout_with_ints:
irqrestore(flags);
return ret;
}
-
+#endif
#endif /* CONFIG_SCHED_HAVE_PARENT */
diff --git a/nuttx/sched/task_setup.c b/nuttx/sched/task_setup.c
index 43ed24b32..b770d46e6 100644
--- a/nuttx/sched/task_setup.c
+++ b/nuttx/sched/task_setup.c
@@ -1,7 +1,7 @@
/****************************************************************************
* sched/task_setup.c
*
- * 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
@@ -49,6 +49,7 @@
#include <nuttx/arch.h>
#include "os_internal.h"
+#include "group_internal.h"
/****************************************************************************
* Definitions
@@ -150,7 +151,8 @@ 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.
+ * Save the task ID of the parent task in the child task's TCB and allocate
+ * a child status structure to catch the child task's exit status.
*
* Parameters:
* tcb - The TCB of the new, child task.
@@ -170,31 +172,57 @@ static inline void task_saveparent(FAR _TCB *tcb, uint8_t ttype)
{
FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
+#if defined(HAVE_GROUP_MEMBERS) || defined(CONFIG_SCHED_CHILD_STATUS)
+ DEBUGASSERT(tcb && tcb->group && rtcb->group);
+#else
+#endif
+
+#ifdef HAVE_GROUP_MEMBERS
+ /* Save the ID of the parent tasks' task group in the child's task group.
+ * Do nothing for pthreads. The parent and the child are both members of
+ * the same task group.
+ */
+
+ if ((tcb->flags & TCB_FLAG_TTYPE_MASK) != TCB_FLAG_TTYPE_PTHREAD)
+ {
+ /* This is a new task in a new task group, we have to copy the ID from
+ * the parent's task group structure to child's task group.
+ */
+
+ tcb->group->tg_pgid = rtcb->group->tg_gid;
+ }
+
+#else
+ DEBUGASSERT(tcb);
+
/* Save the parent task's ID in the child task's TCB. I am not sure if
* this makes sense for the case of pthreads or not, but I don't think it
* is harmful in any event.
*/
- tcb->parent = rtcb->pid;
+ tcb->ppid = rtcb->pid;
+#endif
- /* Exit status only needs to be retained for the case of tasks, however */
+#ifdef CONFIG_SCHED_CHILD_STATUS
+ /* Tasks can also suppress retention of their child status by applying
+ * the SA_NOCLDWAIT flag with sigaction().
+ */
- if (ttype == TCB_FLAG_TTYPE_TASK)
+ if ((rtcb->group->tg_flags && GROUP_FLAG_NOCLDWAIT) == 0)
{
-#ifdef CONFIG_SCHED_CHILD_STATUS
FAR struct child_status_s *child;
/* Make sure that there is not already a structure for this PID in the
* parent TCB. There should not be.
*/
- child = task_findchild(rtcb, tcb->pid);
+ child = group_findchild(rtcb->group, tcb->pid);
DEBUGASSERT(!child);
if (!child)
{
/* Allocate a new status structure */
- child = task_allocchild();
+ child = group_allocchild();
}
/* Did we successfully find/allocate the child status structure? */
@@ -210,16 +238,16 @@ static inline void task_saveparent(FAR _TCB *tcb, uint8_t ttype)
/* Add the entry into the TCB list of children */
- task_addchild(rtcb, child);
+ group_addchild(rtcb->group, child);
}
+ }
#else
- DEBUGASSERT(rtcb->nchildren < UINT16_MAX);
- rtcb->nchildren++;
+ DEBUGASSERT(rtcb->nchildren < UINT16_MAX);
+ rtcb->nchildren++;
#endif
- }
}
#else
-# define task_saveparent(tcb, type)
+# define task_saveparent(tcb,ttype)
#endif
/****************************************************************************
@@ -318,7 +346,9 @@ int task_schedsetup(FAR _TCB *tcb, int priority, start_t start, main_t main,
tcb->flags &= ~TCB_FLAG_TTYPE_MASK;
tcb->flags |= ttype;
- /* Save the task ID of the parent task in the TCB */
+ /* Save the task ID of the parent task in the TCB and allocate
+ * a child status structure.
+ */
task_saveparent(tcb, ttype);
diff --git a/nuttx/sched/task_start.c b/nuttx/sched/task_start.c
index a9cc38dfc..5a32a5dd8 100644
--- a/nuttx/sched/task_start.c
+++ b/nuttx/sched/task_start.c
@@ -94,6 +94,15 @@ void task_start(void)
FAR _TCB *tcb = (FAR _TCB*)g_readytorun.head;
int argc;
+ /* Execute the start hook if one has been registered */
+
+#ifdef CONFIG_SCHED_STARTHOOK
+ if (tcb->starthook)
+ {
+ tcb->starthook(tcb->starthookarg);
+ }
+#endif
+
/* Count how many non-null arguments we are passing */
for (argc = 1; argc <= CONFIG_MAX_TASK_ARGS; argc++)
diff --git a/nuttx/sched/sched_releasefiles.c b/nuttx/sched/task_starthook.c
index a3ef71af4..1cb29349f 100644
--- a/nuttx/sched/sched_releasefiles.c
+++ b/nuttx/sched/task_starthook.c
@@ -1,7 +1,7 @@
/****************************************************************************
- * sched/sched_releasefiles.c
+ * sched/task_start.c
*
- * Copyright (C) 2007, 2008, 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -39,12 +39,29 @@
#include <nuttx/config.h>
-#include <sched.h>
-#include <nuttx/fs/fs.h>
-#include <nuttx/net/net.h>
-#include <nuttx/lib.h>
+#include <nuttx/sched.h>
-#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
+#ifdef CONFIG_SCHED_STARTHOOK
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
/****************************************************************************
* Private Functions
@@ -55,60 +72,29 @@
****************************************************************************/
/****************************************************************************
- * Name: sched_releasefiles
+ * Name: task_starthook
*
* Description:
- * Release file resources attached to a TCB. This file may be called
- * multiple times as a task exists. It will be called as early as possible
- * to support proper closing of complex drivers that may need to wait
- * on external events.
+ * Configure a start hook... a function that will be called on the thread
+ * of the new task before the new task's main entry point is called.
+ * The start hook is useful, for example, for setting up automatic
+ * configuration of C++ constructors.
*
- * Parameters:
- * tcb - tcb of the new task.
+ * Inputs:
+ * tcb - The new, unstarted task task that needs the start hook
+ * starthook - The pointer to the start hook function
+ * arg - The argument to pass to the start hook function.
*
- * Return Value:
+ * Return:
* None
*
- * Assumptions:
- *
****************************************************************************/
-int sched_releasefiles(_TCB *tcb)
+void task_starthook(FAR _TCB *tcb, starthook_t starthook, FAR void *arg)
{
- if (tcb)
- {
-#if CONFIG_NFILE_DESCRIPTORS > 0
- /* Free the file descriptor list */
-
- if (tcb->filelist)
- {
- files_releaselist(tcb->filelist);
- tcb->filelist = NULL;
- }
-
-#if CONFIG_NFILE_STREAMS > 0
- /* Free the stream list */
-
- if (tcb->streams)
- {
- lib_releaselist(tcb->streams);
- tcb->streams = NULL;
- }
-#endif /* CONFIG_NFILE_STREAMS */
-#endif /* CONFIG_NFILE_DESCRIPTORS */
-
-#if CONFIG_NSOCKET_DESCRIPTORS > 0
- /* Free the file descriptor list */
-
- if (tcb->sockets)
- {
- net_releaselist(tcb->sockets);
- tcb->sockets = NULL;
- }
-#endif /* CONFIG_NSOCKET_DESCRIPTORS */
- }
-
- return OK;
+ DEBUGASSERT(tcb);
+ tcb->starthook = starthook;
+ tcb->starthookarg = arg;
}
-#endif /* CONFIG_NFILE_DESCRIPTORS || CONFIG_NSOCKET_DESCRIPTORS */
+#endif /* CONFIG_SCHED_STARTHOOK */
diff --git a/nuttx/sched/task_vfork.c b/nuttx/sched/task_vfork.c
index fece4c596..ac86ddc56 100644
--- a/nuttx/sched/task_vfork.c
+++ b/nuttx/sched/task_vfork.c
@@ -39,6 +39,7 @@
#include <nuttx/config.h>
+#include <sys/wait.h>
#include <stdint.h>
#include <assert.h>
#include <queue.h>
@@ -48,7 +49,7 @@
#include <nuttx/sched.h>
#include "os_internal.h"
-#include "env_internal.h"
+#include "group_internal.h"
/****************************************************************************
* Pre-processor Definitions
@@ -125,17 +126,13 @@ FAR _TCB *task_vforksetup(start_t retaddr)
/* Associate file descriptors with the new task */
#if CONFIG_NFILE_DESCRIPTORS > 0 || CONFIG_NSOCKET_DESCRIPTORS > 0
- ret = sched_setuptaskfiles(child);
+ ret = group_setuptaskfiles(child);
if (ret != OK)
{
goto errout_with_tcb;
}
#endif
- /* Clone the parent's task environment */
-
- (void)env_dup(child);
-
/* Get the priority of the parent task */
#ifdef CONFIG_PRIORITY_INHERITANCE
diff --git a/nuttx/sched/timer_initialize.c b/nuttx/sched/timer_initialize.c
index 05980bb1a..2651469ef 100644
--- a/nuttx/sched/timer_initialize.c
+++ b/nuttx/sched/timer_initialize.c
@@ -137,7 +137,7 @@ void weak_function timer_initialize(void)
* resources are referenced.
*
* Parameters:
- * pid - the task ID of the thread that exitted
+ * pid - the task ID of the thread that exited
*
* Return Value:
* None